Go to the documentation of this file.
17 #ifndef TRACKING__TRACK_CLASS_VARIABLE_HPP_
18 #define TRACKING__TRACK_CLASS_VARIABLE_HPP_
21 #include <autoware_auto_perception_msgs/msg/object_classification.hpp>
40 template<std::u
int8_t kClassificationConstant>
42 public std::integral_constant<std::uint8_t, kClassificationConstant> {};
54 template<
typename StateT>
59 "The provided type must represent a GenericState type.");
62 using VariableT = decltype(variable);
64 StateT::template index_of<VariableT>() == VariableT::value,
65 "The index of the variable must correspond to the integral constant stored inside of "
66 "this variable class.");
73 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN>,
74 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::CAR>,
75 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK>,
76 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::BUS>,
77 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER>,
78 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE>,
79 ClassificationVariable<autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE>,
86 #endif // TRACKING__TRACK_CLASS_VARIABLE_HPP_
Forward-declare is_state trait.
Definition: generic_state.hpp:51
A struct to create a variable type from a given uint8_t value.
Definition: track_class_variable.hpp:41
common::state_vector::FloatState< ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::CAR >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::BUS >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE >, ClassificationVariable< autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN > > ObjectClassificationState
A common state used for classification in the tracker.
Definition: track_class_variable.hpp:80
A representation of a generic state vectors with specified variables.
Definition: generic_state.hpp:60
Contains base tag structs that define variables and traits to check if a type is one.
This file defines a class for a generic state vector representation.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
A tag struct used to disambiguate variables from other types.
Definition: variable.hpp:40
static void assert_indices_match_classification_constants()
Check that all the indices in the state vector correspond to the integral constant that the variable ...
Definition: track_class_variable.hpp:55
constexpr COMMON_PUBLIC std::enable_if_t< I==sizeof...(TypesT)> visit(std::tuple< TypesT... > &, Callable) noexcept
Visit every element in a tuple.
Definition: type_traits.hpp:80