|
@@ -12,21 +12,21 @@ Locater::Locater():mp_yolo_detector(0),mp_point_sift(0),mp_cnn3d(0)
|
|
|
Locater::~Locater()
|
|
|
{}
|
|
|
|
|
|
-ERROR_CODE Locater::get_error()
|
|
|
+Error_manager Locater::get_error()
|
|
|
{
|
|
|
return SUCCESS;
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::init(Locate::LocateParameter parameter)
|
|
|
+Error_manager Locater::init(Measure::LocateParameter parameter)
|
|
|
{
|
|
|
- ERROR_CODE code;
|
|
|
+ Error_manager code;
|
|
|
{
|
|
|
int point_size = parameter.seg_parameter().point_size();
|
|
|
int cls_num = parameter.seg_parameter().cls_num();
|
|
|
double freq = parameter.seg_parameter().freq();
|
|
|
std::string graph = parameter.seg_parameter().graph();
|
|
|
std::string cpkt = parameter.seg_parameter().cpkt();
|
|
|
- Locate::Area3d area = parameter.seg_parameter().area();
|
|
|
+ Measure::Area3d area = parameter.seg_parameter().area();
|
|
|
pcl::PointXYZ minp(area.x_min(), area.y_min(), area.z_min());
|
|
|
pcl::PointXYZ maxp(area.x_max(), area.y_max(), area.z_max());
|
|
|
|
|
@@ -35,11 +35,12 @@ ERROR_CODE Locater::init(Locate::LocateParameter parameter)
|
|
|
|
|
|
std::string graph_file = graph;
|
|
|
std::string cpkt_file = cpkt;
|
|
|
- LOG(INFO)<<"init pointSift net ...";
|
|
|
+ LOG(INFO)<<"init pointSift net graph:"<<graph;
|
|
|
code=mp_point_sift->init(graph_file,cpkt_file);
|
|
|
+ LOG(ERROR)<<"------------------------------yolo-1";
|
|
|
if(code!=SUCCESS)
|
|
|
{
|
|
|
- LOG(ERROR)<<"Init pointSIFT net Failed ... "<<code;
|
|
|
+ LOG(ERROR)<<"Init pointSIFT net Failed ... "<<code.to_string();
|
|
|
return code;
|
|
|
}
|
|
|
}
|
|
@@ -53,6 +54,7 @@ ERROR_CODE Locater::init(Locate::LocateParameter parameter)
|
|
|
float freq = parameter.yolo_parameter().freq();
|
|
|
std::string cfg = parameter.yolo_parameter().cfg();
|
|
|
std::string weights = parameter.yolo_parameter().weights();
|
|
|
+ LOG(ERROR)<<"------------------------------yolo-";
|
|
|
mp_yolo_detector = new YoloDetector(cfg, weights, min_x, max_x, min_y, max_y, freq);
|
|
|
|
|
|
}
|
|
@@ -68,16 +70,16 @@ ERROR_CODE Locater::init(Locate::LocateParameter parameter)
|
|
|
LOG(INFO)<<"Init 3dcnn ...";
|
|
|
std::string weights = parameter.net_3dcnn_parameter().weights_file();
|
|
|
code=mp_cnn3d->init(weights);
|
|
|
- if(SUCCESS!=code)
|
|
|
+ if(code!=SUCCESS)
|
|
|
{
|
|
|
- LOG(ERROR)<<"Init 3dcnn failed : "<<code;
|
|
|
+ LOG(ERROR)<<"Init 3dcnn failed : "<<code.to_string();
|
|
|
return code;
|
|
|
}
|
|
|
return SUCCESS;
|
|
|
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::execute_task(Task_Base* task,double time_out)
|
|
|
+Error_manager Locater::execute_task(Task_Base* task,double time_out)
|
|
|
{
|
|
|
LOG(INFO)<<"NEW LOCATE TASK ==============================================================================";
|
|
|
Locate_information locate_information;
|
|
@@ -93,7 +95,7 @@ ERROR_CODE Locater::execute_task(Task_Base* task,double time_out)
|
|
|
}
|
|
|
Locate_task* locate_task=(Locate_task*)task;
|
|
|
locate_task->update_statu(TASK_SIGNED);
|
|
|
- ERROR_CODE code;
|
|
|
+ Error_manager code;
|
|
|
///第一步,获取task中input点云,文件保存路径
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud_input=locate_task->get_locate_cloud();
|
|
|
std::string save_path=locate_task->get_save_path();
|
|
@@ -107,7 +109,7 @@ ERROR_CODE Locater::execute_task(Task_Base* task,double time_out)
|
|
|
std::lock_guard<std::mutex> t_lock(m_mutex_lock);
|
|
|
locate_task->update_statu(TASK_WORKING);
|
|
|
code=locate(t_cloud_input,locate_information,save_path);
|
|
|
- if(SUCCESS!=code)
|
|
|
+ if(code!=SUCCESS)
|
|
|
{
|
|
|
locate_task->update_statu(TASK_OVER,"Locate Failed");
|
|
|
return code;
|
|
@@ -118,23 +120,20 @@ ERROR_CODE Locater::execute_task(Task_Base* task,double time_out)
|
|
|
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
+Error_manager Locater::locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
std::vector<YoloBox>& boxes, std::string work_dir)
|
|
|
{
|
|
|
if(cloud_in.get()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"yolo input cloud uninit";
|
|
|
- return LOCATER_YOLO_INPUT_CLOUD_UNINIT;
|
|
|
+ return Error_manager(LOCATER_YOLO_INPUT_CLOUD_UNINIT,NORMAL,"yolo input cloud uninit");
|
|
|
}
|
|
|
if(cloud_in->size()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate_yolo input cloud empty";
|
|
|
- return LOCATER_INPUT_YOLO_CLOUD_EMPTY;
|
|
|
+ return Error_manager(LOCATER_INPUT_YOLO_CLOUD_EMPTY,NORMAL,"locate_yolo input cloud empty");
|
|
|
}
|
|
|
if(mp_yolo_detector==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate_yolo yolo is not init";
|
|
|
- return LOCATER_YOLO_UNINIT;
|
|
|
+ return Error_manager(LOCATER_YOLO_UNINIT,NORMAL,"locate_yolo yolo is not init");
|
|
|
}
|
|
|
//1,根据点云区域,调整yolo边界参数,边界参数必须保证长宽 1:1
|
|
|
pcl::PointXYZ min_point,max_point;
|
|
@@ -153,36 +152,29 @@ ERROR_CODE Locater::locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
mp_yolo_detector->set_region(yolo_minx,yolo_maxx,yolo_miny,yolo_maxy,m_locate_parameter.yolo_parameter().freq());
|
|
|
//2,识别车辆位置
|
|
|
boxes.clear();
|
|
|
- ERROR_CODE code=mp_yolo_detector->detect(cloud_in,boxes,work_dir);
|
|
|
- if(code!=SUCCESS)
|
|
|
- {
|
|
|
- LOG(ERROR)<<"Yolo detect failed : "<<code;
|
|
|
- }
|
|
|
- return code;
|
|
|
+ return mp_yolo_detector->detect(cloud_in,boxes,work_dir);
|
|
|
+
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox> boxes,
|
|
|
+Error_manager Locater::locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox> boxes,
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_targe, std::string work_dir)
|
|
|
{
|
|
|
if(cloud_in.get()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"sift input cloud uninit";
|
|
|
- return LOCATER_SIFT_INPUT_CLOUD_UNINIT;
|
|
|
+ return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,NORMAL,"sift input cloud uninit");
|
|
|
}
|
|
|
if(cloud_in->size()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate_sift input cloud empty";
|
|
|
- return LOCATER_SIFT_INPUT_CLOUD_EMPTY;
|
|
|
+ return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,NORMAL,"locate_sift input cloud empty");
|
|
|
}
|
|
|
if(mp_point_sift==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"Point Sift unInit ";
|
|
|
- return LOCATER_POINTSIFT_UNINIT;
|
|
|
+ return Error_manager(LOCATER_POINTSIFT_UNINIT,NORMAL,"Point Sift unInit");
|
|
|
}
|
|
|
//第一步,根据点云边界调整PointSIft 参数
|
|
|
pcl::PointXYZ min_point,max_point;
|
|
|
pcl::getMinMax3D(*cloud_in,min_point,max_point);
|
|
|
- ERROR_CODE code ;
|
|
|
+ Error_manager code ;
|
|
|
code=mp_point_sift->set_region(min_point,max_point);
|
|
|
if(code!=SUCCESS)
|
|
|
{
|
|
@@ -230,26 +222,23 @@ ERROR_CODE Locater::locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, st
|
|
|
return SUCCESS;
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::locate_wheel_rotate_rect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,cv::RotatedRect& rotate_rect,
|
|
|
+Error_manager Locater::locate_wheel_rotate_rect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,cv::RotatedRect& rotate_rect,
|
|
|
std::string work_dir)
|
|
|
{
|
|
|
if(cloud.get()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"3dcnn input cloud uninit";
|
|
|
- return LOCATER_3DCNN_INPUT_CLOUD_UNINIT;
|
|
|
+ return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_UNINIT,NORMAL,"3dcnn input cloud uninit");
|
|
|
}
|
|
|
if(cloud->size()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate_3dcnn input cloud empty";
|
|
|
- return LOCATER_3DCNN_INPUT_CLOUD_EMPTY;
|
|
|
+ return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,NORMAL,"locate_3dcnn input cloud empty");
|
|
|
}
|
|
|
if(mp_cnn3d==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate_wheel 3dcnn is not init";
|
|
|
- return LOCATER_3DCNN_UNINIT;
|
|
|
+ return Error_manager(LOCATER_3DCNN_UNINIT,NORMAL,"locate_wheel 3dcnn is not init");
|
|
|
}
|
|
|
//识别车轮
|
|
|
- ERROR_CODE code;
|
|
|
+ Error_manager code;
|
|
|
code=mp_cnn3d->predict(cloud,rotate_rect,work_dir);
|
|
|
if(code!=SUCCESS)
|
|
|
{
|
|
@@ -258,20 +247,21 @@ ERROR_CODE Locater::locate_wheel_rotate_rect(pcl::PointCloud<pcl::PointXYZ>::Ptr
|
|
|
//根据plc限制判断合法性
|
|
|
if(rotate_rect.center.y>=930 || rotate_rect.center.y<=200)
|
|
|
{
|
|
|
- LOG(ERROR)<<" Y is out of range by plc (200 , 900) Y:"<<rotate_rect.center.x;
|
|
|
- return LOCATER_Y_OUT_RANGE_BY_PLC;
|
|
|
+ char description[255]={0};
|
|
|
+ sprintf(description,"Y is out of range by plc (200 , 900) Y:%.2f",rotate_rect.center.y);
|
|
|
+ return Error_manager(LOCATER_Y_OUT_RANGE_BY_PLC,NORMAL,description);
|
|
|
}
|
|
|
return SUCCESS;
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car,float& height)
|
|
|
+Error_manager Locater::measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car,float& height)
|
|
|
{
|
|
|
if(cloud_car.get()==0)
|
|
|
{
|
|
|
LOG(ERROR)<<"measure height input cloud uninit";
|
|
|
- return LOCATER_MEASURE_HEIGHT_CLOUD_UNINIT;
|
|
|
+ return Error_manager(LOCATER_MEASURE_HEIGHT_CLOUD_UNINIT,NORMAL,"measure height input cloud uninit");
|
|
|
}
|
|
|
if(cloud_car->size()==0)
|
|
|
{
|
|
@@ -283,30 +273,30 @@ ERROR_CODE Locater::measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car
|
|
|
height=max_point.z;
|
|
|
if(height<1000||height>2000)
|
|
|
{
|
|
|
- return LOCATER_HEIGHT_OUT_RANGE;
|
|
|
+ char description[255]={0};
|
|
|
+ sprintf(description,"height(%.1f) is out of range(1000,2000)",height);
|
|
|
+ return Error_manager(LOCATER_HEIGHT_OUT_RANGE,NORMAL,description);
|
|
|
}
|
|
|
return SUCCESS;
|
|
|
}
|
|
|
|
|
|
-ERROR_CODE Locater::locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
+Error_manager Locater::locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
Locate_information& locate_information, std::string work_dir)
|
|
|
{
|
|
|
if(cloud_in.get()==0)
|
|
|
{
|
|
|
- LOG(ERROR)<<"locate input cloud is not init";
|
|
|
- return LOCATER_INPUT_CLOUD_UNINIT;
|
|
|
+ return Error_manager(LOCATER_INPUT_CLOUD_UNINIT,NORMAL,"locate input cloud is not init");
|
|
|
}
|
|
|
if(cloud_in->size()==0) {
|
|
|
- LOG(ERROR)<<"input cloud is empty";
|
|
|
- return LOCATER_INPUT_CLOUD_EMPTY;
|
|
|
+ return Error_manager(LOCATER_INPUT_CLOUD_EMPTY,NORMAL,"input cloud is empty");
|
|
|
}
|
|
|
//置初始结果为错误
|
|
|
locate_information.locate_correct=false;
|
|
|
- ERROR_CODE code;
|
|
|
+ Error_manager code;
|
|
|
//第一步 yolo定位车辆外接矩形
|
|
|
std::vector<YoloBox> t_yolo_boxes;
|
|
|
code=locate_yolo(cloud_in,t_yolo_boxes,work_dir);
|
|
|
- if(SUCCESS!=code)
|
|
|
+ if(code!=SUCCESS)
|
|
|
{
|
|
|
return code;
|
|
|
}
|
|
@@ -322,7 +312,7 @@ ERROR_CODE Locater::locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
//第三步,计算车辆高度
|
|
|
float height_car=0;
|
|
|
code=measure_height(cloud_car,height_car);
|
|
|
- if(SUCCESS!=code)
|
|
|
+ if(code!=SUCCESS)
|
|
|
{
|
|
|
return code;
|
|
|
}
|
|
@@ -330,7 +320,7 @@ ERROR_CODE Locater::locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
|
|
|
//第四步,识别轮胎,并根据轮胎数量计算旋转矩形
|
|
|
cv::RotatedRect rotate_rect;
|
|
|
code=locate_wheel_rotate_rect(cloud_car,rotate_rect,work_dir);
|
|
|
- if(SUCCESS!=code)
|
|
|
+ if(code!=SUCCESS)
|
|
|
{
|
|
|
return code;
|
|
|
}
|