21 #include <boost/circular_buffer.hpp> 31 namespace perception {
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
107 std::array<Eigen::Vector3d, 100>
drops;
std::array< Eigen::Vector3d, 100 > drops
Definition: object.h:107
RadarObjectSupplement radar_supplement
Definition: object.h:115
std::size_t drop_num
Definition: object.h:108
MotionState
Definition: object_types.h:80
LidarObjectSupplement lidar_supplement
Definition: object.h:114
Eigen::Vector3f Vector3f
Definition: base_map_fwd.h:29
FusionObjectSupplement fusion_supplement
Definition: object.h:117
std::string ToString() const
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::vector< float > sub_type_probs
Definition: object.h:78
Definition: object_supplement.h:249
Eigen::Matrix3f acceleration_uncertainty
Definition: object.h:97
bool b_cipv
Definition: object.h:110
Eigen::Vector3f size_variance
Definition: object.h:66
double tracking_time
Definition: object.h:100
ObjectSubType sub_type
Definition: object.h:76
Eigen::Matrix3f velocity_uncertainty
Definition: object.h:89
float theta
Definition: object.h:54
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
std::vector< float > type_probs
Definition: object.h:73
double latest_tracked_time
Definition: object.h:102
PointCloud< PointD > polygon
Definition: object.h:45
Definition: object_supplement.h:34
int track_id
Definition: object.h:85
Eigen::Matrix3f Matrix3f
Definition: base_map_fwd.h:27
Eigen::Vector3f velocity
Definition: object.h:87
Definition: vehicle_struct.h:22
float velocity_confidence
Definition: object.h:93
CarLight car_light
Definition: object.h:112
Eigen::Vector3f size
Definition: object.h:64
ObjectType type
Definition: object.h:71
Eigen::Matrix3f center_uncertainty
Definition: object.h:60
Eigen::Vector3d center
Definition: object.h:58
Definition: object_supplement.h:78
CameraObjectSupplement camera_supplement
Definition: object.h:116
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Object()
MotionState motion_state
Definition: object.h:105
std::shared_ptr< const Object > ObjectConstPtr
Definition: object.h:124
Eigen::Vector3f acceleration
Definition: object.h:95
Definition: object_supplement.h:104
Eigen::Vector3d anchor_point
Definition: object.h:68
float confidence
Definition: object.h:81
ObjectType
Definition: object_types.h:26
float theta_variance
Definition: object.h:56
Eigen::Vector3f direction
Definition: object.h:49
ObjectSubType
Definition: object_types.h:63
bool velocity_converged
Definition: object.h:91
std::shared_ptr< Object > ObjectPtr
Definition: object.h:123