Commit 029344bd authored by oscar's avatar oscar

提交显示修正逻辑

parent 9a600ae6
......@@ -23,7 +23,7 @@ float to360(float rot_y,float lidar_x_angle)
//SDK_LOG(SDK_INFO, "rot_y = %f, angle = %f", rot_y, angle);
float tmp_angle = 0.0f;
float car_angle = angle / _PI_ * 180.0f;
tmp_angle = car_angle - lidar_x_angle;
tmp_angle = lidar_x_angle - car_angle;
//SDK_LOG(SDK_INFO, "car_angle = %f, tmp_angle = %f,lidar_x_angle = %f", car_angle, tmp_angle, lidar_x_angle);
tmp_angle += 360;
while (tmp_angle > 360)
......@@ -109,10 +109,6 @@ void TrackingRos::Init(ros::NodeHandle& nh)
memcpy(m, f, sizeof(float) * 4);
SDK_LOG(SDK_INFO, "data = %f,%f,%f,%f", m[0], m[1], m[2], m[3]);
float rot_y = 1.427666;
float rot_y_a = to360(rot_y, m_lidar_x_angle);
}
void TrackingRos::TrackingCallBackFunc(const jfx_common_msgs::det_tracking_arrayConstPtr& msg)//接受ros发过来的消息
......@@ -282,9 +278,7 @@ void TrackingRos::ThreadTrackingProcess()
//修正rot_y值,变为角度
float rot_y_angle = obj.rot_y;
obj.rot_y = to360(obj.rot_y, m_lidar_x_angle);
float rot_y_a = obj.rot_y / 180 * 3.14159265;
//SDK_LOG(SDK_INFO, "rot_y = %f, rot_y_angle = %f", rot_y_angle, rot_y_a);
rot_y_angle = rot_y_a;
jsk_recognition_msgs::BoundingBox box = {};
box.label = obj.obj_id;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment