#include <object.h>
|
| int | id = -1 |
| |
| PointCloud< PointD > | polygon |
| |
| Eigen::Vector3f | direction = Eigen::Vector3f(1, 0, 0) |
| |
| float | theta = 0.0f |
| |
| float | theta_variance = 0.0f |
| |
| Eigen::Vector3d | center = Eigen::Vector3d(0, 0, 0) |
| |
| Eigen::Matrix3f | center_uncertainty |
| |
| Eigen::Vector3f | size = Eigen::Vector3f(0, 0, 0) |
| |
| Eigen::Vector3f | size_variance = Eigen::Vector3f(0, 0, 0) |
| |
| Eigen::Vector3d | anchor_point = Eigen::Vector3d(0, 0, 0) |
| |
| ObjectType | type = ObjectType::UNKNOWN |
| |
| std::vector< float > | type_probs |
| |
| ObjectSubType | sub_type = ObjectSubType::UNKNOWN |
| |
| std::vector< float > | sub_type_probs |
| |
| float | confidence = 1.0f |
| |
| int | track_id = -1 |
| |
| Eigen::Vector3f | velocity = Eigen::Vector3f(0, 0, 0) |
| |
| Eigen::Matrix3f | velocity_uncertainty |
| |
| bool | velocity_converged = true |
| |
| float | velocity_confidence = 1.0f |
| |
| Eigen::Vector3f | acceleration = Eigen::Vector3f(0, 0, 0) |
| |
| Eigen::Matrix3f | acceleration_uncertainty |
| |
| double | tracking_time = 0.0 |
| |
| double | latest_tracked_time = 0.0 |
| |
| MotionState | motion_state = MotionState::UNKNOWN |
| |
| std::array< Eigen::Vector3d, 100 > | drops |
| |
| std::size_t | drop_num = 0 |
| |
| bool | b_cipv = false |
| |
| CarLight | car_light |
| |
| LidarObjectSupplement | lidar_supplement |
| |
| RadarObjectSupplement | radar_supplement |
| |
| CameraObjectSupplement | camera_supplement |
| |
| FusionObjectSupplement | fusion_supplement |
| |
◆ Object()
| apollo::perception::base::Object::Object |
( |
| ) |
|
◆ Reset()
| void apollo::perception::base::Object::Reset |
( |
| ) |
|
◆ ToString()
| std::string apollo::perception::base::Object::ToString |
( |
| ) |
const |
◆ acceleration
| Eigen::Vector3f apollo::perception::base::Object::acceleration = Eigen::Vector3f(0, 0, 0) |
◆ acceleration_uncertainty
| Eigen::Matrix3f apollo::perception::base::Object::acceleration_uncertainty |
◆ anchor_point
| Eigen::Vector3d apollo::perception::base::Object::anchor_point = Eigen::Vector3d(0, 0, 0) |
◆ b_cipv
| bool apollo::perception::base::Object::b_cipv = false |
◆ camera_supplement
◆ car_light
| CarLight apollo::perception::base::Object::car_light |
◆ center
| Eigen::Vector3d apollo::perception::base::Object::center = Eigen::Vector3d(0, 0, 0) |
◆ center_uncertainty
| Eigen::Matrix3f apollo::perception::base::Object::center_uncertainty |
◆ confidence
| float apollo::perception::base::Object::confidence = 1.0f |
◆ direction
| Eigen::Vector3f apollo::perception::base::Object::direction = Eigen::Vector3f(1, 0, 0) |
◆ drop_num
| std::size_t apollo::perception::base::Object::drop_num = 0 |
◆ drops
| std::array<Eigen::Vector3d, 100> apollo::perception::base::Object::drops |
◆ fusion_supplement
◆ id
| int apollo::perception::base::Object::id = -1 |
◆ latest_tracked_time
| double apollo::perception::base::Object::latest_tracked_time = 0.0 |
◆ lidar_supplement
◆ motion_state
◆ polygon
◆ radar_supplement
◆ size
| Eigen::Vector3f apollo::perception::base::Object::size = Eigen::Vector3f(0, 0, 0) |
◆ size_variance
| Eigen::Vector3f apollo::perception::base::Object::size_variance = Eigen::Vector3f(0, 0, 0) |
◆ sub_type
◆ sub_type_probs
| std::vector<float> apollo::perception::base::Object::sub_type_probs |
◆ theta
| float apollo::perception::base::Object::theta = 0.0f |
◆ theta_variance
| float apollo::perception::base::Object::theta_variance = 0.0f |
◆ track_id
| int apollo::perception::base::Object::track_id = -1 |
◆ tracking_time
| double apollo::perception::base::Object::tracking_time = 0.0 |
◆ type
◆ type_probs
| std::vector<float> apollo::perception::base::Object::type_probs |
◆ velocity
| Eigen::Vector3f apollo::perception::base::Object::velocity = Eigen::Vector3f(0, 0, 0) |
◆ velocity_confidence
| float apollo::perception::base::Object::velocity_confidence = 1.0f |
◆ velocity_converged
| bool apollo::perception::base::Object::velocity_converged = true |
◆ velocity_uncertainty
| Eigen::Matrix3f apollo::perception::base::Object::velocity_uncertainty |
The documentation for this struct was generated from the following file: