33 const Eigen::Affine3d& pose) {
38 const Eigen::Affine3d& pose,
39 const Eigen::Vector3d& global_to_local_offset,
54 Eigen::Matrix3d rotation = pose.rotation();
64 cloud_world.resize(cloud.
size());
65 for (
size_t i = 0; i < cloud.
size(); ++i) {
66 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
67 Eigen::Vector3d pt_world = pose * pt;
68 cloud_world[i].x = pt_world(0);
69 cloud_world[i].y = pt_world(1);
70 cloud_world[i].z = pt_world(2);
71 cloud_world[i].rcs = cloud[i].rcs;
72 cloud_world[i].velocity = cloud[i].velocity;
73 cloud_world[i].comp_vel = cloud[i].comp_vel;
98 cloud_world.resize(cloud.size());
99 for (
size_t i = 0; i < cloud.size(); ++i) {
100 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
102 cloud_world[i].x = pt_world(0);
103 cloud_world[i].y = pt_world(1);
104 cloud_world[i].z = pt_world(2);
105 cloud_world[i].rcs = cloud[i].rcs;
106 cloud_world[i].velocity = cloud[i].velocity;
107 cloud_world[i].comp_vel = cloud[i].comp_vel;
116 for (
int i = 0; i < 4; ++i) {
117 corners[i] = Eigen::Vector3d::Zero();
120 center = Eigen::Vector3d::Zero();
128 size = Eigen::Vector3d::Zero();
154 state = Eigen::Vector4d::Zero();
172 const Eigen::Vector3d& global_to_local_offset,
175 AttachObject(obj_ptr, pose, global_to_local_offset, sensor);
181 object_ptr = base::ObjectPool::Instance().Get();
221 obj->theta = std::atan2(obj->velocity[1], obj->velocity[0]);
223 obj->theta = std::atan2(obj->direction[1], obj->direction[0]);
237 std::ostringstream oos;
258 for (
size_t i = 0; i < feature_len; ++i) {
void ComputeHistogram(int bin_size, float *feature)
Eigen::Matrix< T, 3, 1 > CalculateRadarCentroid(const base::AttributeRadarPointCloud< base::RadarPoint< T > > &cloud)
AttributeRadarPointCloud< RadarPointF > RadarPointFCloud
AttributeRadarPointCloud< RadarPointD > RadarPointDCloud
std::shared_ptr< Object > ObjectPtr
apollo::perception::base::RadarPointCloud< RadarPointF > RadarPointFCloud
std::shared_ptr< TrackedObject > TrackedObjectPtr
Eigen::Vector3d output_center
Eigen::Vector3d lane_direction
Eigen::Vector3d measured_barycenter_velocity
float GetVelThreshold(base::ObjectPtr obj) const
Get vehicle threshold
void ToObject(base::ObjectPtr obj_ptr) const
Convert tracked object to base object
Eigen::Matrix4d state_covariance
Eigen::Vector3d selected_measured_velocity
float convergence_confidence
std::vector< float > shape_features
Eigen::Vector3d corners[4]
Eigen::Matrix3d output_velocity_uncertainty
Eigen::Matrix3d belief_velocity_online_covariance
Eigen::Vector3d global_local_offset
void TransformObjectCloudToWorld()
Transform object cloud to world
Eigen::Vector3d selected_measured_acceleration
Eigen::Vector3d measured_corners_velocity[4]
Eigen::Matrix3d velocity_covariance
std::vector< float > shape_features_full
Eigen::Vector3d belief_acceleration
Eigen::Affine3d sensor_to_local_pose
Eigen::Vector3d output_size
Eigen::Vector3d measured_center_velocity
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())
Attach object
void CopyFrom(std::shared_ptr< TrackedObject > rhs, bool is_deep)
Copy from tracked object
size_t histogram_bin_size
Eigen::Vector3d belief_velocity
Eigen::Vector3d direction
Eigen::Vector3d barycenter
Eigen::Vector3d motion_score
Eigen::Matrix4d measurement_covariance
Eigen::Vector3d output_direction
Eigen::Vector3d output_velocity
Eigen::Vector3d belief_velocity_gain
int boostup_need_history_size
base::SensorInfo sensor_info
base::ObjectPtr object_ptr
Eigen::Vector3d belief_anchor_point
void ComputeShapeFeatures()
Compute shape features
Eigen::Vector3d anchor_point
void Reset()
Reset all data
Eigen::Vector3d measured_nearest_corner_velocity
std::string ToString() const
Transform tracked data state to string