|
Apollo 11.0
自动驾驶开放平台
|
#include <tracked_object.h>
Public 成员函数 | |
| TrackedObject ()=default | |
| TrackedObject (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose) | |
| TrackedObject (const TrackedObject &rhs)=default | |
| TrackedObject & | operator= (const TrackedObject &rhs)=default |
| void | Reset () |
| Reset all data | |
| void | Reset (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0) |
| Reset all data | |
| std::string | ToString () const |
| Transform tracked data state to string | |
| void | ComputeShapeFeatures () |
| Compute shape features | |
| void | AttachObject (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0) |
| Attach object | |
| void | TransformObjectCloudToWorld () |
| Transform object cloud to world | |
| void | CopyFrom (std::shared_ptr< TrackedObject > rhs, bool is_deep) |
| Copy from tracked object | |
| void | ToObject (base::ObjectPtr obj_ptr) const |
| Convert tracked object to base object | |
| float | GetVelThreshold (base::ObjectPtr obj) const |
| Get vehicle threshold | |
在文件 tracked_object.h 第 32 行定义.
|
default |
| apollo::perception::lidar::TrackedObject::TrackedObject | ( | base::ObjectPtr | obj_ptr, |
| const Eigen::Affine3d & | pose | ||
| ) |
在文件 tracked_object.cc 第 32 行定义.
|
default |
| void apollo::perception::lidar::TrackedObject::AttachObject | ( | base::ObjectPtr | obj_ptr, |
| const Eigen::Affine3d & | pose, | ||
| const Eigen::Vector3d & | global_to_local_offset = Eigen::Vector3d::Zero(), |
||
| const base::SensorInfo & | sensor = base::SensorInfo(), |
||
| double | timestamp = 0.0 |
||
| ) |
Attach object
| obj_ptr | |
| pose | |
| global_to_local_offset | |
| sensor |
在文件 tracked_object.cc 第 37 行定义.
| void apollo::perception::lidar::TrackedObject::ComputeShapeFeatures | ( | ) |
Compute shape features
在文件 tracked_object.cc 第 296 行定义.
| void apollo::perception::lidar::TrackedObject::CopyFrom | ( | std::shared_ptr< TrackedObject > | rhs, |
| bool | is_deep | ||
| ) |
Copy from tracked object
| rhs | |
| is_deep |
| float apollo::perception::lidar::TrackedObject::GetVelThreshold | ( | base::ObjectPtr | obj | ) | const |
Get vehicle threshold
| obj |
在文件 tracked_object.cc 第 238 行定义.
|
default |
| void apollo::perception::lidar::TrackedObject::Reset | ( | ) |
Reset all data
在文件 tracked_object.cc 第 145 行定义.
| void apollo::perception::lidar::TrackedObject::Reset | ( | base::ObjectPtr | obj_ptr, |
| const Eigen::Affine3d & | pose, | ||
| const Eigen::Vector3d & | global_to_local_offset = Eigen::Vector3d::Zero(), |
||
| const base::SensorInfo & | sensor = base::SensorInfo(), |
||
| double | timestamp = 0.0 |
||
| ) |
Reset all data
| obj_ptr | |
| pose | |
| global_to_local_offset | |
| sensor |
在文件 tracked_object.cc 第 221 行定义.
| void apollo::perception::lidar::TrackedObject::ToObject | ( | base::ObjectPtr | obj_ptr | ) | const |
Convert tracked object to base object
| obj_ptr |
在文件 tracked_object.cc 第 245 行定义.
| std::string apollo::perception::lidar::TrackedObject::ToString | ( | ) | const |
Transform tracked data state to string
在文件 tracked_object.cc 第 284 行定义.
| void apollo::perception::lidar::TrackedObject::TransformObjectCloudToWorld | ( | ) |
Transform object cloud to world
在文件 tracked_object.cc 第 128 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::anchor_point |
在文件 tracked_object.h 第 141 行定义.
| float apollo::perception::lidar::TrackedObject::association_score = 0.0f |
在文件 tracked_object.h 第 119 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::barycenter |
在文件 tracked_object.h 第 140 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_acceleration |
在文件 tracked_object.h 第 185 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_anchor_point |
在文件 tracked_object.h 第 183 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_velocity |
在文件 tracked_object.h 第 184 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_velocity_gain |
在文件 tracked_object.h 第 186 行定义.
| Eigen::Matrix3d apollo::perception::lidar::TrackedObject::belief_velocity_online_covariance |
在文件 tracked_object.h 第 190 行定义.
| int apollo::perception::lidar::TrackedObject::boostup_need_history_size = 0 |
在文件 tracked_object.h 第 176 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::center |
在文件 tracked_object.h 第 139 行定义.
| bool apollo::perception::lidar::TrackedObject::converged = true |
在文件 tracked_object.h 第 178 行定义.
| float apollo::perception::lidar::TrackedObject::convergence_confidence = 0.0f |
在文件 tracked_object.h 第 179 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::corners[4] |
在文件 tracked_object.h 第 138 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::detection_center |
在文件 tracked_object.h 第 143 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::detection_corners[4] |
在文件 tracked_object.h 第 144 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::direction |
在文件 tracked_object.h 第 147 行定义.
| double apollo::perception::lidar::TrackedObject::direction_converged = false |
在文件 tracked_object.h 第 213 行定义.
| double apollo::perception::lidar::TrackedObject::direction_convergence_confidence = 0.0 |
在文件 tracked_object.h 第 212 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::direction_state |
在文件 tracked_object.h 第 208 行定义.
| Eigen::Matrix3d apollo::perception::lidar::TrackedObject::direction_state_covariance |
在文件 tracked_object.h 第 209 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::global_local_offset |
在文件 tracked_object.h 第 225 行定义.
| size_t apollo::perception::lidar::TrackedObject::histogram_bin_size = 10 |
在文件 tracked_object.h 第 116 行定义.
| bool apollo::perception::lidar::TrackedObject::is_background = false |
在文件 tracked_object.h 第 154 行定义.
| bool apollo::perception::lidar::TrackedObject::is_fake = false |
在文件 tracked_object.h 第 124 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::lane_direction |
在文件 tracked_object.h 第 148 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_barycenter_velocity |
在文件 tracked_object.h 第 161 行定义.
| int apollo::perception::lidar::TrackedObject::measured_big_velocity_age |
在文件 tracked_object.h 第 170 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_center_velocity |
在文件 tracked_object.h 第 162 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_corners_velocity[4] |
在文件 tracked_object.h 第 164 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_center_velocity |
在文件 tracked_object.h 第 167 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_history_center_velocity |
在文件 tracked_object.h 第 168 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_history_corners_velocity[4] |
在文件 tracked_object.h 第 169 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_history_center_velocity |
在文件 tracked_object.h 第 166 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_history_corners_velocity[4] |
在文件 tracked_object.h 第 165 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_nearest_corner_velocity |
在文件 tracked_object.h 第 163 行定义.
| Eigen::Matrix4d apollo::perception::lidar::TrackedObject::measurement_covariance |
在文件 tracked_object.h 第 194 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::motion_score |
在文件 tracked_object.h 第 203 行定义.
| base::ObjectPtr apollo::perception::lidar::TrackedObject::object_ptr |
在文件 tracked_object.h 第 136 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_angular |
在文件 tracked_object.h 第 210 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_center |
在文件 tracked_object.h 第 221 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_direction |
在文件 tracked_object.h 第 220 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_size |
在文件 tracked_object.h 第 222 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_velocity |
在文件 tracked_object.h 第 218 行定义.
| Eigen::Matrix3d apollo::perception::lidar::TrackedObject::output_velocity_uncertainty |
在文件 tracked_object.h 第 219 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::selected_measured_acceleration |
在文件 tracked_object.h 第 182 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::selected_measured_velocity |
在文件 tracked_object.h 第 181 行定义.
| base::SensorInfo apollo::perception::lidar::TrackedObject::sensor_info |
在文件 tracked_object.h 第 223 行定义.
| Eigen::Affine3d apollo::perception::lidar::TrackedObject::sensor_to_local_pose |
在文件 tracked_object.h 第 131 行定义.
| std::vector<float> apollo::perception::lidar::TrackedObject::shape_features |
在文件 tracked_object.h 第 114 行定义.
| std::vector<float> apollo::perception::lidar::TrackedObject::shape_features_full |
在文件 tracked_object.h 第 115 行定义.
| Eigen::Vector3d apollo::perception::lidar::TrackedObject::size |
在文件 tracked_object.h 第 149 行定义.
| Eigen::Vector4d apollo::perception::lidar::TrackedObject::state |
在文件 tracked_object.h 第 193 行定义.
| Eigen::Matrix4d apollo::perception::lidar::TrackedObject::state_covariance |
在文件 tracked_object.h 第 195 行定义.
| double apollo::perception::lidar::TrackedObject::timestamp = 0.0 |
在文件 tracked_object.h 第 156 行定义.
| int apollo::perception::lidar::TrackedObject::track_id = -1 |
在文件 tracked_object.h 第 125 行定义.
| double apollo::perception::lidar::TrackedObject::tracking_time = 0.0 |
在文件 tracked_object.h 第 126 行定义.
| base::ObjectType apollo::perception::lidar::TrackedObject::type = base::ObjectType::UNKNOWN |
在文件 tracked_object.h 第 151 行定义.
| std::vector<float> apollo::perception::lidar::TrackedObject::type_probs |
在文件 tracked_object.h 第 153 行定义.
| double apollo::perception::lidar::TrackedObject::update_quality = 0.0 |
在文件 tracked_object.h 第 180 行定义.
| bool apollo::perception::lidar::TrackedObject::valid = false |
在文件 tracked_object.h 第 177 行定义.
| Eigen::Matrix3d apollo::perception::lidar::TrackedObject::velocity_covariance |
在文件 tracked_object.h 第 189 行定义.