Commit a56807f7 authored by oscar's avatar oscar

提交修改

parent 1e3afd5a
......@@ -202,7 +202,7 @@ void TrackingRos::Init(ros::NodeHandle& nh)
SDK_LOG(SDK_INFO, "trans = [%s]", GetMatrixStr(m_trans, 4, 4).c_str());
SDK_LOG(SDK_INFO, "kitti2origin = [%s]", GetMatrixStr(m_kitti2origin,4,4).c_str());
ADD_DEF_LOG(1, "tracking.csv");
SDK_IDX_LOG(1, SDK_INFO, "date,frameNum,time,id,input_radian,input_angle,predict_radian,predict_angle,output_radian,output_angle,input_x,input_y,input_z,input_l,input_w,input_h,predict_x,predict_y,predict_z,predict_l,predict_w,preditc_h,output_x,output_y,output_z,output_l,output_w,output_h,output_rot_y,v_x,v_y,v_z,lat,lon");
SDK_IDX_LOG(1, SDK_INFO, "date,frameNum,time,id,input_radian,input_angle,predict_radian,predict_angle,output_radian,output_angle,input_type,input_x,input_y,input_z,input_l,input_w,input_h,last_type,predict_x,predict_y,predict_z,predict_l,predict_w,preditc_h,output_type,output_x,output_y,output_z,output_l,output_w,output_h,output_rot_y,v_x,v_y,v_z,lat,lon");
//m_coordinate.Init(value[0][0], value[0][1], value[0][2], value[0][3], value[1][0], value[1][1]);
m_pub = nh.advertise<jfx_common_msgs::det_tracking_array>("/tracking_res", 100);
......@@ -344,6 +344,7 @@ void TrackingRos::ThreadTrackingProcess()
{
jfx_common_msgs::det_tracking obj = {};
jfx_common_msgs::det_tracking input_obj = {};
int last_type = -1;
int is_need_send = 0;//是否需要发送
if (updateId.find(iter.first) != updateId.end())
{
......@@ -374,6 +375,7 @@ void TrackingRos::ThreadTrackingProcess()
obj.Long = pos[1];
//SDK_LOG(SDK_INFO, "lat = %.10f, lon = %.10f",obj.Lat,obj.Long);
}
last_type = iter.second->m_obj->type;
iter.second->m_obj = std::make_shared<jfx_common_msgs::det_tracking>(obj);
}
else
......@@ -429,11 +431,11 @@ void TrackingRos::ThreadTrackingProcess()
// predict[0], predict[1], predict[2], predict[4], predict[5], predict[6], predict[3],
// obj.x, obj.y, obj.z, obj.l, obj.w, obj.h, obj.rot_y, iter.second->GetProb());
//date,frame,id,input_radian,input_angle,predict_radian,predict_angle,output_radian,output_angle,input_x,input_y,input_z,input_l,input_w,input_h,predict_x,predict_y,predict_z,predict_l,predict_w,preditc_h,output_x,output_y,output_z,output_l,output_w,output_h,output_rot_y,v_x,v_y,v_z,lat,lon
SDK_IDX_LOG(1, SDK_INFO, "%s,%d,%llu,%llu,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%.10f,%.10f",
SDK_IDX_LOG(1, SDK_INFO, "%s,%d,%llu,%llu,%f,%f,%f,%f,%f,%f,%d,%f,%f,%f,%f,%f,%f,%d,%f,%f,%f,%f,%f,%f,%d,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%.10f,%.10f",
GetTimeStr(obj.frame).c_str(), m_frameNum, obj.frame, iter.first, input_obj.rot_y, input_obj.rot_y * 180 / _PI_, predict[3], predict[3] * 180 / _PI_, rot_y_angle, rot_y_angle * 180 / _PI_,
input_obj.x, input_obj.y, input_obj.z, input_obj.l, input_obj.w, input_obj.h,
predict[0], predict[1], predict[2], predict[4], predict[5], predict[6],
obj.x, obj.y, obj.z, obj.l, obj.w, obj.h, obj.rot_y, obj.v_x, obj.v_y, obj.v_z, obj.Lat, obj.Long);
input_obj.type,input_obj.x, input_obj.y, input_obj.z, input_obj.l, input_obj.w, input_obj.h,
last_type,predict[0], predict[1], predict[2], predict[4], predict[5], predict[6],
obj.type,obj.x, obj.y, obj.z, obj.l, obj.w, obj.h, obj.rot_y, obj.v_x, obj.v_y, obj.v_z, obj.Lat, obj.Long);
}
jsk_recognition_msgs::BoundingBox box = {};
......
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