Commit f9d5276f authored by oscar's avatar oscar

提交前相机距离配置

parent 1270e60a
......@@ -291,7 +291,8 @@ void TrackingRos::Init(ros::NodeHandle& nh)
SDK_LOG(SDK_INFO, "camera_debug_type = %d", m_camera_debug_type);
nh.param<int32_t>("right_left_camera_len", m_right_left_camera_len, 15);
SDK_LOG(SDK_INFO, "right_left_camera_len = %d", m_right_left_camera_len);
nh.param<int32_t>("front_camera_len", m_front_camera_len, 0);
SDK_LOG(SDK_INFO, "front_camera_len = %d", m_front_camera_len);
YAML::Node config = YAML::LoadFile(file.c_str());
auto cfg = config["TRACKING"];
......@@ -559,6 +560,14 @@ void TrackingRos::TrackingCameraCallBackFunc(const jfx_common_msgs::InferResesCo
}
else
continue;
if (i == 0)
{
if (m_front_camera_len != 0)
{
if (x < m_front_camera_len && objMsg.type != 4 && objMsg.type != 5)
continue;
}
}
if(i == 0 && m_camera_one_center_type != 2)
objMsg.x = objMsg.x + (objMsg.l / 2);
int duplicate = 0;
......
......@@ -66,4 +66,5 @@ public:
int m_camera_cloud_merge_type = 0;//0是使用距离判断,1是使用iou判断
int m_camera_debug_type = 0;//调试相机类型是否修改为7,0是正常,1是调试为7
int m_right_left_camera_len = 15;//左右相机的显示距离米数
int m_front_camera_len = 0;//-前相机过滤的距离米数,0是不过滤,70就是过滤70米,但不过滤行人和机动车
};
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