Browse Source

修改错误码为Error_manager

zx 5 years ago
parent
commit
d60852df82

+ 9 - 2
CMakeLists.txt

@@ -34,14 +34,21 @@ aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/plc PLC_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/locate LOCATE_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/terminor TERMINOR_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/task TASK_MANAGER_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/error_code ERROR_SRC )
 
 #add_executable(LidarMeasure ./main.cpp ${LASER_SRC} ${PLC_SRC} ${TERMINOR_SRC} ${LOCATE_SRC} ${TASK_MANAGER_SRC})
 #
 
-add_executable(locate  main.cpp ${LOCATE_SRC} ${PLC_SRC} ${TERMINOR_SRC} ${TASK_MANAGER_SRC} ${LASER_SRC})
-target_link_libraries(locate ${OpenCV_LIBS}
+add_executable(LocateSample ./test/locate_sample.cpp  ${ERROR_SRC} ${LOCATE_SRC} ${TASK_MANAGER_SRC})
+target_link_libraries(LocateSample ${OpenCV_LIBS}
         ${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ipopt libtensorflow_cc.so
         tf_3dcnn_api.so pointSIFT_API.so dark.so /usr/local/lib/libmodbus.so /usr/local/lib/libglog.a
         /usr/local/lib/libgflags.a /usr/local/lib/liblivox_sdk_static.a /usr/local/apr/lib/libapr-1.a nnxx nanomsg)
 
+#add_executable(locate  main.cpp ${LOCATE_SRC} ${PLC_SRC} ${TERMINOR_SRC} ${TASK_MANAGER_SRC} ${LASER_SRC} ${ERROR_SRC})
+#target_link_libraries(locate ${OpenCV_LIBS}
+#        ${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ipopt libtensorflow_cc.so
+#        tf_3dcnn_api.so pointSIFT_API.so dark.so /usr/local/lib/libmodbus.so /usr/local/lib/libglog.a
+#        /usr/local/lib/libgflags.a /usr/local/lib/liblivox_sdk_static.a /usr/local/apr/lib/libapr-1.a nnxx nanomsg)
+
 

+ 0 - 75
error.h

@@ -1,75 +0,0 @@
-#ifndef LIDAR_MEASURE_ERROR__H
-#define LIDAR_MEASURE_ERROR__H
-enum ERROR_CODE
-{
-    SUCCESS=0x00000000,
-
-
-    LASER_INIT_FAILED	=	0x010102FF,
-
-
-
-PLC_INIT_ERROR=0x02010000,
-PLC_UNKNOWN_ERROR,
-PLC_SET_CALLBACK_ERROR,
-PLC_IP_PORT_ERROR,
-PLC_SLAVE_ID_ERROR,
-PLC_CONNECTION_FAILED,
-PLC_READ_FAILED,
-PLC_WRITE_FAILED,
-PLC_NOT_ENOUGH_DATA_ERROR,
-
-    //Locater.cpp error from 0x0301000-0x030100FF
-    LOCATER_TASK_INIT_CLOUD_EMPTY=0x03010000,
-    LOCATER_TASK_ERROR,
-    LOCATER_TASK_INPUT_CLOUD_UNINIT,
-    LOCATER_INPUT_CLOUD_EMPTY,
-    LOCATER_YOLO_UNINIT,
-    LOCATER_POINTSIFT_UNINIT,
-    LOCATER_3DCNN_UNINIT,
-    LOCATER_INPUT_YOLO_CLOUD_EMPTY,
-    LOCATER_Y_OUT_RANGE_BY_PLC,
-    LOCATER_MEASURE_HEIGHT_CLOUD_UNINIT,
-    LOCATER_MEASURE_HEIGHT_CLOUD_EMPTY,
-    LOCATER_HEIGHT_OUT_RANGE,
-    LOCATER_ANGLE_OUT_RANGE,
-    LOCATER_INPUT_CLOUD_UNINIT,
-
-
-    //point sift from 0x03010100-0x030101FF
-    LOCATER_SIFT_INIT_FAILED=0x03010100,
-    LOCATER_SIFT_INPUT_CLOUD_UNINIT,
-    LOCATER_SIFT_PREDICT_FAILED,
-    LOCATER_SIFT_CREATE_INPUT_DATA_FAILED,
-    LOCATER_SIFT_FILTE_OBS_FAILED,
-    LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,
-    LOCATER_SIFT_INPUT_CLOUD_EMPTY,
-    LOCATER_SIFT_PREDICT_NO_CAR_POINT,
-
-    //yolo from 0x03010200-0x030102FF
-    LOCATER_YOLO_DETECT_FAILED=0x03010200,
-    LOCATER_YOLO_DETECT_NO_TARGET,
-    LOCATER_YOLO_PARAMETER_INVALID,
-    LOCATER_YOLO_INPUT_CLOUD_UNINIT,
-
-    //3dcnn from 0x03010300-0x030103FF
-    LOCATER_3DCNN_INIT_FAILED=0x03010300,
-    LOCATER_3DCNN_INPUT_CLOUD_UNINIT,
-    LOCATER_3DCNN_PREDICT_FAILED,
-    LOCATER_3DCNN_VERIFY_RECT_FAILED_3,
-    LOCATER_3DCNN_VERIFY_RECT_FAILED_4,
-    LOCATER_3DCNN_KMEANS_FAILED,
-    LOCATER_3DCNN_IIU_FAILED,
-    LOCATER_3DCNN_INPUT_CLOUD_EMPTY,
-
-    //terminor error from 0x04010000-0x0401FFFF
-
-    //terminor_command_executor.cpp from 0x04010200-0x040102FF
-    TERMINOR_NOT_READY=0x04010200,
-    TERMINOR_INPUT_LASER_NULL,
-    TERMINOR_INPUT_PLC_NULL,
-    TERMINOR_INPUT_LOCATER_NULL,
-    TERMINOR_CREATE_WORKING_THREAD_FAILED
-};
-
-#endif

+ 12 - 0
error_code/error_code.cpp

@@ -17,6 +17,7 @@ Error_manager::Error_manager()
 //拷贝构造
 Error_manager::Error_manager(const Error_manager & error_manager)
 {
+    pm_error_description=0;
     this->m_error_code = error_manager.m_error_code;
     this->m_error_level = error_manager.m_error_level;
     reallocate_memory_and_copy_string(error_manager.pm_error_description, error_manager.m_description_length);
@@ -25,6 +26,7 @@ Error_manager::Error_manager(const Error_manager & error_manager)
 //赋值构造
 Error_manager::Error_manager(Error_code error_code, Error_level error_level, char* p_error_description, int description_length)
 {
+    pm_error_description=NULL;
     m_error_code = error_code;
     m_error_level = error_level;
     reallocate_memory_and_copy_string(p_error_description, description_length);
@@ -33,6 +35,7 @@ Error_manager::Error_manager(Error_code error_code, Error_level error_level, cha
 //赋值构造
 Error_manager::Error_manager(Error_code error_code, Error_level error_level , std::string & error_aggregate_string)
 {
+    pm_error_description=NULL;
     m_error_code = error_code;
     m_error_level = error_level;
     reallocate_memory_and_copy_string(error_aggregate_string);
@@ -403,6 +406,15 @@ void Error_manager::reallocate_memory_and_copy_string(std::string & error_aggreg
     }
 }
 
+bool Error_manager::operator==(Error_code code)
+{
+    return m_error_code==code;
+}
+
+bool Error_manager::operator!=(Error_code code)
+{
+    return m_error_code!=code;
+}
 
 
 

+ 68 - 0
error_code/error_code.h

@@ -74,6 +74,70 @@ enum Error_code
     LIVOX_ERROR_BASE                = 0x01020000,
     LIVOX_START_FAILE               = 0x01020101,
 
+
+    //PLC error code  ...
+    PLC_INIT_ERROR=0x02010000,
+    PLC_UNKNOWN_ERROR,
+    PLC_SET_CALLBACK_ERROR,
+    PLC_IP_PORT_ERROR,
+    PLC_SLAVE_ID_ERROR,
+    PLC_CONNECTION_FAILED,
+    PLC_READ_FAILED,
+    PLC_WRITE_FAILED,
+    PLC_NOT_ENOUGH_DATA_ERROR,
+
+    //Locater.cpp error from 0x0301000-0x030100FF
+        LOCATER_TASK_INIT_CLOUD_EMPTY=0x03010000,
+    LOCATER_TASK_ERROR,
+    LOCATER_TASK_INPUT_CLOUD_UNINIT,
+    LOCATER_INPUT_CLOUD_EMPTY,
+    LOCATER_YOLO_UNINIT,
+    LOCATER_POINTSIFT_UNINIT,
+    LOCATER_3DCNN_UNINIT,
+    LOCATER_INPUT_YOLO_CLOUD_EMPTY,
+    LOCATER_Y_OUT_RANGE_BY_PLC,
+    LOCATER_MEASURE_HEIGHT_CLOUD_UNINIT,
+    LOCATER_MEASURE_HEIGHT_CLOUD_EMPTY,
+    LOCATER_HEIGHT_OUT_RANGE,
+    LOCATER_ANGLE_OUT_RANGE,
+    LOCATER_INPUT_CLOUD_UNINIT,
+
+
+    //point sift from 0x03010100-0x030101FF
+        LOCATER_SIFT_INIT_FAILED=0x03010100,
+    LOCATER_SIFT_INPUT_CLOUD_UNINIT,
+    LOCATER_SIFT_PREDICT_FAILED,
+    LOCATER_SIFT_CREATE_INPUT_DATA_FAILED,
+    LOCATER_SIFT_FILTE_OBS_FAILED,
+    LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,
+    LOCATER_SIFT_INPUT_CLOUD_EMPTY,
+    LOCATER_SIFT_PREDICT_NO_CAR_POINT,
+
+    //yolo from 0x03010200-0x030102FF
+        LOCATER_YOLO_DETECT_FAILED=0x03010200,
+    LOCATER_YOLO_DETECT_NO_TARGET,
+    LOCATER_YOLO_PARAMETER_INVALID,
+    LOCATER_YOLO_INPUT_CLOUD_UNINIT,
+
+    //3dcnn from 0x03010300-0x030103FF
+    LOCATER_3DCNN_INIT_FAILED=0x03010300,
+    LOCATER_3DCNN_INPUT_CLOUD_UNINIT,
+    LOCATER_3DCNN_PREDICT_FAILED,
+    LOCATER_3DCNN_VERIFY_RECT_FAILED_3,
+    LOCATER_3DCNN_VERIFY_RECT_FAILED_4,
+    LOCATER_3DCNN_KMEANS_FAILED,
+    LOCATER_3DCNN_IIU_FAILED,
+    LOCATER_3DCNN_INPUT_CLOUD_EMPTY,
+
+    //terminor error from 0x04010000-0x0401FFFF
+
+    //terminor_command_executor.cpp from 0x04010200-0x040102FF
+    TERMINOR_NOT_READY=0x04010200,
+    TERMINOR_INPUT_LASER_NULL,
+    TERMINOR_INPUT_PLC_NULL,
+    TERMINOR_INPUT_LOCATER_NULL,
+    TERMINOR_CREATE_WORKING_THREAD_FAILED
+
 };
 
 //错误等级,用来做故障处理
@@ -195,6 +259,10 @@ public://外部接口函数
     //错误码转字符串的简易版,可支持cout<<
     //return     错误汇总的string
     std::string to_string();
+    //重载==号操作符
+    bool operator==(Error_code code);
+    //重载!=操作符
+    bool operator!=(Error_code code);
 
 
 

+ 1 - 1
laser/laser.cpp

@@ -13,7 +13,7 @@ Laser_base::~Laser_base()
 {
 
 }
-ERROR_CODE Laser_base::get_error()
+Error_manager Laser_base::get_error()
 {
     return SUCCESS;
 }

+ 2 - 2
laser/laser.h

@@ -4,14 +4,14 @@
 
 #ifndef LASER_H
 #define LASER_H
-#include "../error.h"
+#include "../error_code/error_code.h"
 
 class Laser_base
 {
 public:
     Laser_base();
     ~Laser_base();
-    ERROR_CODE get_error();
+    Error_manager get_error();
 };
 
 

+ 3 - 3
locate/YoloDetector.cpp

@@ -9,7 +9,7 @@ void YoloDetector::free_img(image_t m)
     }
 }
 
-ERROR_CODE YoloDetector::set_region(float minx, float maxx, float miny, float maxy,float freq)
+Error_manager YoloDetector::set_region(float minx, float maxx, float miny, float maxy,float freq)
 {
     if(m_maxx<=m_minx || m_maxy<=m_miny || m_freq<=0)
     {
@@ -46,7 +46,7 @@ YoloDetector::~YoloDetector()
 #endif
 }
 
-ERROR_CODE YoloDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox>& boxes, std::string save_dir)
+Error_manager YoloDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox>& boxes, std::string save_dir)
 {
 	boxes.clear();
 #if YOLO_API_USED
@@ -130,7 +130,7 @@ ERROR_CODE YoloDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, st
 }
 
 
-ERROR_CODE YoloDetector::detect(cv::Mat& l, cv::Mat& r, std::vector<YoloBox>& boxes,std::string save_dir)
+Error_manager YoloDetector::detect(cv::Mat& l, cv::Mat& r, std::vector<YoloBox>& boxes,std::string save_dir)
 {
 #if YOLO_API_USED
 	int w = int((m_maxx - m_minx) / m_freq);

+ 4 - 4
locate/YoloDetector.h

@@ -6,7 +6,7 @@
 #include <pcl/point_types.h>
 #include <pcl/common/common.h>
 #include "yolo_v2_class.hpp"
-#include "../error.h"
+#include "../error_code/error_code.h"
 
 #define YOLO_API_USED	1
 
@@ -25,14 +25,14 @@ public:
 	//设置输入点云的边界,识别的时候根据边界投影到图像
 	//输入边界的长款比必须是1:1,否则会出现图像扭曲
 	//freq:表示多长一个像素点
-    ERROR_CODE set_region(float minx, float maxx, float miny, float maxy,float freq);
+    Error_manager set_region(float minx, float maxx, float miny, float maxy,float freq);
 	virtual ~YoloDetector();
     //识别函数, 将点云数据转换成图像格式保存,该函数已经过期(第一版算法,点云由两个雷达扫描)
     //l:左边雷达扫描数据; r:右边雷达扫描数据
     //save_dir:中间数据保存路径
-	ERROR_CODE detect(cv::Mat& l, cv::Mat& r, std::vector<YoloBox>& boxes,std::string save_dir);
+	Error_manager detect(cv::Mat& l, cv::Mat& r, std::vector<YoloBox>& boxes,std::string save_dir);
 	//将点云投影成图像, 识别车辆外接矩形框
-	ERROR_CODE detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox>& boxes, std::string save_dir);
+	Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<YoloBox>& boxes, std::string save_dir);
 protected:
     //释放图像内存
     void free_img(image_t img);

+ 24 - 28
locate/cnn3d_segmentation.cpp

@@ -1,7 +1,6 @@
 #include "cnn3d_segmentation.h"
 #include "tf_wheel_3Dcnn_api.h"
 #include <iostream>
-#include "../error.h"
 #include <glog/logging.h>
 #include <pcl/segmentation/extract_clusters.h>
 #include <pcl/kdtree/kdtree.h>
@@ -150,7 +149,7 @@ cv::RotatedRect minAreaRect_cloud(std::vector<cv::Point2f> centers)
 	return rect;
 }
 
-ERROR_CODE Cnn3d_segmentation::set_parameter(int l, int w, int h,int freq,int classes)
+Error_manager Cnn3d_segmentation::set_parameter(int l, int w, int h,int freq,int classes)
 {
     m_lenth = l;
     m_width = w;
@@ -173,7 +172,7 @@ Cnn3d_segmentation::~Cnn3d_segmentation()
 	tf_wheel_3dcnn_close();
 }
 
-ERROR_CODE Cnn3d_segmentation::init(std::string weights)
+Error_manager Cnn3d_segmentation::init(std::string weights)
 {
 
 	if (0 != tf_wheel_3dcnn_init(weights, m_lenth,m_width,m_height))
@@ -328,7 +327,7 @@ std::vector<cv::Point2f> Cnn3d_segmentation::kmeans(pcl::PointCloud<pcl::PointXY
 	return rets;*/
 }
 
-ERROR_CODE Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
+Error_manager Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
 {
 	if (points.size() == 4)
 	{
@@ -355,17 +354,18 @@ ERROR_CODE Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
         }
         double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
         if (fabs(cosa) >= 0.13) {
-            LOG(ERROR) << " angle cos >0.13 =" << cosa << "  i=" << max_index;
-            return LOCATER_3DCNN_VERIFY_RECT_FAILED_4;
+            char description[255]={0};
+            sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
+            return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
         }
 
         float width=std::min(l1,l2);
         float length=std::max(l1,l2);
         if(width<1400 || width >2000 || length >3300 ||length < 2200)
         {
-            LOG(ERROR)<<"\t width<1400 || width >2100 || length >3300 ||length < 2100 "
-                <<"  length:"<<length<<"  width:"<<width;
-            return LOCATER_3DCNN_VERIFY_RECT_FAILED_4;
+            char description[255]={0};
+            sprintf(description,"width<1400 || width >2100 || length >3300 ||length < 2100 l:%.1f,w:%.1f",length,width);
+            return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
         }
 
         double d = distance(pc, points[3]);
@@ -404,8 +404,9 @@ ERROR_CODE Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
         }
         double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
         if (fabs(cosa) >= 0.12) {
-            LOG(ERROR) << "3 wheels angle cos >0.12 =" << cosa << "  i=" << max_index;
-            return LOCATER_3DCNN_VERIFY_RECT_FAILED_3;
+            char description[255]={0};
+            sprintf(description,"3 wheels angle cos value(%.2f) >0.12 ",cosa);
+            return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,NORMAL,description);
         }
 
         double l=std::max(l1,l2);
@@ -423,9 +424,10 @@ ERROR_CODE Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
         }
         else
         {
-            LOG(INFO) << "3 wheels rectangle verify Failed  cos angle=" << cosa << "  L=" << l
-                      << "  w=" << w;
-            return LOCATER_3DCNN_VERIFY_RECT_FAILED_3;
+
+            char description[255]={0};
+            sprintf(description,"3 wheels rectangle verify Failed  cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
+            return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,NORMAL,description);
         }
 
     }
@@ -447,13 +449,12 @@ void save_cloudT(std::string txt, pcl::PointCloud<pcl::PointXYZ>& pCloud)
     os.close();
 }
 
-ERROR_CODE Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, cv::RotatedRect& rect,
+Error_manager Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, cv::RotatedRect& rect,
     std::string cluster_file_path)
 {
     if(cloud->size()==0)
     {
-        LOG(ERROR)<<" 3dcnn predict input cloud empty";
-        return LOCATER_3DCNN_INPUT_CLOUD_EMPTY;
+        return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,NORMAL,"3dcnn predict input cloud empty");
     }
 
 	pcl::PointXYZ minp, maxp;
@@ -475,7 +476,7 @@ ERROR_CODE Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
 	{
 		free(data);
 		free(pout);
-		return LOCATER_3DCNN_PREDICT_FAILED;
+		return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"3dcnn first predict failed");
 	}
 
 	std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> cloudout = decodeCloud(*cloud, pout, min_x, max_x, min_y, max_y, min_z, max_z);
@@ -491,13 +492,11 @@ ERROR_CODE Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
 
 	if (cloudout.size() == 0)
 	{
-		LOG(ERROR) << "tf pred classes ==0";
-		return LOCATER_3DCNN_PREDICT_FAILED;
+		return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"tf pred classes ==0");
 	}
 	if (cloudout[0]->size() == 0)
 	{
-		LOG(ERROR) << "tf pred class[wheel].points size ==0";
-		return LOCATER_3DCNN_PREDICT_FAILED;
+		return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"tf pred class[wheel].points size ==0");
 	}
     //离群点过滤
 	pcl::StatisticalOutlierRemoval<pcl::PointXYZRGB> sorfilter(true); // Initializing with true will allow us to extract the removed indices
@@ -508,8 +507,7 @@ ERROR_CODE Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
 
 	if (cloudout[0]->size() < 4 )
 	{
-		LOG(ERROR) <<  "tf pred wheel points size <4";
-		return LOCATER_3DCNN_PREDICT_FAILED;
+		return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"tf pred wheel points size <4");
 	}
 	//kmeans
 	std::vector<cv::Point2f> centers = kmeans(cloudout[0], cluster_file_path);
@@ -520,13 +518,11 @@ ERROR_CODE Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
     }
 	if (centers.size() != 4 && centers.size()!=3)
 	{
-		LOG(ERROR) << "\t 3dcnn cluster center size != 4 & 3";
-		return LOCATER_3DCNN_KMEANS_FAILED;
+		return Error_manager(LOCATER_3DCNN_KMEANS_FAILED,NORMAL,"3dcnn cluster center size != 4 & 3");
 	}
-	ERROR_CODE code=isRect(centers);
+	Error_manager code=isRect(centers);
 	if(code!=SUCCESS)
 	{
-		LOG(ERROR) << "\t 3dcnn rectangle verify failed   ";
 		return code;
 	}
     if(centers.size()==3)

+ 5 - 5
locate/cnn3d_segmentation.h

@@ -5,7 +5,7 @@
 #include <pcl/point_types.h>
 #include <pcl/common/common.h>
 #include <string>
-#include "../error.h"
+#include "../error_code/error_code.h"
 
 /*
  * 3dcnn网络识别车两中轮胎点
@@ -15,17 +15,17 @@ class  Cnn3d_segmentation
 public:
 	Cnn3d_segmentation(int l,int w,int h,int freq,int nClass);
 	//设置3dcnn网络参数
-    ERROR_CODE set_parameter(int l, int w, int h,int freq,int classes);
+    Error_manager set_parameter(int l, int w, int h,int freq,int classes);
 	virtual ~Cnn3d_segmentation();
 	//初始化网络参数
 	//weights:参数文件
-	virtual ERROR_CODE init(std::string weights);
+	virtual Error_manager init(std::string weights);
 
 	//预测
 	//cloud:输入点云
 	//rect:输出旋转矩形框
 	//save_dir:中间文件保存路径
-	virtual ERROR_CODE predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, cv::RotatedRect& rect, std::string save_dir);
+	virtual Error_manager predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, cv::RotatedRect& rect, std::string save_dir);
 
 protected:
     //根据设置的参数将点云转换成网络输入数格式
@@ -37,7 +37,7 @@ protected:
 protected:
 	//判断矩形框是否找到
 	//points:输入轮子中心点, 只能是3或者4个
-	ERROR_CODE isRect(std::vector<cv::Point2f>& points);
+	Error_manager isRect(std::vector<cv::Point2f>& points);
 	//kmeans算法聚类,拆分四个轮子,返回四轮中心
 	//cloud:输入点云
 	std::vector<cv::Point2f> kmeans(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string cluster_file_path);

+ 3 - 4
locate/locate_task.cpp

@@ -3,7 +3,6 @@
 //
 
 #include "locate_task.h"
-#include "../error.h"
 #include <glog/logging.h>
 Locate_task::Locate_task()
 {
@@ -14,7 +13,7 @@ Locate_task::~Locate_task()
 
 }
 
-ERROR_CODE Locate_task::set_locate_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
+Error_manager Locate_task::set_locate_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
 {
     if(cloud.get()==0)
     {
@@ -38,7 +37,7 @@ Locate_information Locate_task::get_locate_information()
     return m_locate_information;
 }
 
-ERROR_CODE Locate_task::set_locate_information(Locate_information information)
+Error_manager Locate_task::set_locate_information(Locate_information information)
 {
     memcpy(&m_locate_information,&information,sizeof(Locate_information));
     return SUCCESS;
@@ -49,7 +48,7 @@ std::string Locate_task::get_save_path()
     return m_save_path;
 }
 
-ERROR_CODE Locate_task::set_save_path(std::string path)
+Error_manager Locate_task::set_save_path(std::string path)
 {
     m_save_path=path;
     return SUCCESS;

+ 4 - 4
locate/locate_task.h

@@ -5,7 +5,7 @@
 #ifndef LOCATE_TASK_H
 #define LOCATE_TASK_H
 #include "../task/task_command_manager.h"
-#include "../error.h"
+#include "../error_code/error_code.h"
 #include <pcl/point_types.h>
 #include <pcl/common/common.h>
 
@@ -33,17 +33,17 @@ public:
     Locate_task();
     ~Locate_task();
     //设置测量输入点云
-    ERROR_CODE set_locate_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
+    Error_manager set_locate_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
     //获取输入点云
     pcl::PointCloud<pcl::PointXYZ>::Ptr get_locate_cloud();
     //获取测量结果
     Locate_information get_locate_information();
     //设置测量结果
-    ERROR_CODE set_locate_information(Locate_information information);
+    Error_manager set_locate_information(Locate_information information);
     //获取文件存放路径
     std::string get_save_path();
     //设置文件村昂路径
-    ERROR_CODE set_save_path(std::string path);
+    Error_manager set_save_path(std::string path);
 protected:
     //测量算法输入点云
     pcl::PointCloud<pcl::PointXYZ>::Ptr         m_locate_cloud_ptr;

+ 44 - 54
locate/locater.cpp

@@ -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;
     }

+ 10 - 10
locate/locater.h

@@ -6,7 +6,7 @@
 #define LOCATER_H
 #include "locate_task.h"
 #include "locater_parameter.pb.h"
-#include "../error.h"
+#include "../error_code/error_code.h"
 #include "point_sift_segmentation.h"
 #include "YoloDetector.h"
 #include "cnn3d_segmentation.h"
@@ -19,41 +19,41 @@ public:
     Locater();
     ~Locater();
     //初始化测量算法参数
-    ERROR_CODE init(Locate::LocateParameter parameter);
+    Error_manager init(Measure::LocateParameter parameter);
     //获取测量模块状态(错误码);返回是否能执行任务,以及不能执行任务的原因
-    ERROR_CODE get_error();
+    Error_manager get_error();
     //执行任务,
     //task:测量任务
     //time_out:超时时间,单位秒
-    ERROR_CODE execute_task(Task_Base* task,double time_out=5);
+    Error_manager execute_task(Task_Base* task,double time_out=5);
 protected:
     //测量算法函数
     //cloud_in:输入点云
     //locate_information:测量结果
     //work_dir:中间文件保存路径
-    ERROR_CODE locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
+    Error_manager locate(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
         Locate_information& locate_information, std::string work_dir);
     //yolo定位车辆外接矩形
     //cloud_in:输入点云,定位算法内部不会修改点云内容
     //boxes:定位到的外接box框
     //work_dir:中间文件输出路径
-    ERROR_CODE locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
+    Error_manager locate_yolo(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
         std::vector<YoloBox>& boxes, std::string work_dir);
     //根据yolo识别结果, 利用PointSift从场景中分割车辆点云
     //cloud:输入点云
     //boxes:yolo识别结果
     //cloud_target:车辆点云
     //work_dir:中间文件保存路径
-    ERROR_CODE locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::vector<YoloBox> boxes,
+    Error_manager locate_sift(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::vector<YoloBox> boxes,
                            pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_targe, std::string work_dir);
     //输入汽车点云,识别轮胎,并找到轮胎的外接旋转矩形;
-    ERROR_CODE locate_wheel_rotate_rect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,cv::RotatedRect& rotate_rect,
+    Error_manager locate_wheel_rotate_rect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,cv::RotatedRect& rotate_rect,
         std::string work_dir);
     //根据汽车点云计算车高
     //cloud_car:车辆点云
-    ERROR_CODE measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car,float& height);
+    Error_manager measure_height(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_car,float& height);
 private:
-    Locate::LocateParameter           m_locate_parameter;
+    Measure::LocateParameter           m_locate_parameter;
     Point_sift_segmentation*                mp_point_sift;
     YoloDetector*                           mp_yolo_detector;
     Cnn3d_segmentation*                     mp_cnn3d;

File diff suppressed because it is too large
+ 266 - 266
locate/locater_parameter.pb.cc


File diff suppressed because it is too large
+ 216 - 216
locate/locater_parameter.pb.h


+ 1 - 1
locate/locater_parameter.proto

@@ -1,5 +1,5 @@
 syntax = "proto2";
-package Locate;
+package Measure;
 
 message Area3d
 {

+ 6 - 6
locate/point_sift_segmentation.cpp

@@ -27,15 +27,14 @@ Point_sift_segmentation::Point_sift_segmentation(int point_size, int cls, float
 	m_maxp = maxp;
 }
 
-ERROR_CODE Point_sift_segmentation::set_region(pcl::PointXYZ minp, pcl::PointXYZ maxp)
+Error_manager Point_sift_segmentation::set_region(pcl::PointXYZ minp, pcl::PointXYZ maxp)
 {
     m_minp = minp;
     m_maxp = maxp;
     if(m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y)
     {
-        LOG(ERROR)<<"Point sift set region invalid :m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y  "
-                    <<LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED;
-        return LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED;
+        return Error_manager(LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,NORMAL,
+            "Point sift set region invalid :m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y ");
     }
     return SUCCESS;
 }
@@ -44,13 +43,14 @@ Point_sift_segmentation::~Point_sift_segmentation()
 {
 }
 
-ERROR_CODE Point_sift_segmentation::init(std::string graph, std::string cpkt)
+Error_manager Point_sift_segmentation::init(std::string graph, std::string cpkt)
 {
 	if (!Load(graph, cpkt))
 	{
 		LOG(ERROR) << "\tpointSIFT Init ERROR:" << LastError();
 		return LOCATER_SIFT_INIT_FAILED;
 	}
+
     //创建空数据,第一次初始化后空跑
 	float* cloud_data = (float*)malloc(m_point_num * 3 * sizeof(float));
 	float* output = (float*)malloc(m_point_num * m_cls_num * sizeof(float));
@@ -149,7 +149,7 @@ bool Point_sift_segmentation::Create_data(pcl::PointCloud<pcl::PointXYZ>::Ptr cl
 	return true;
 }
 
-ERROR_CODE Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
+Error_manager Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
     std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_seg, std::string save_dir)
 {
     if(cloud->size()==0)

+ 4 - 4
locate/point_sift_segmentation.h

@@ -2,7 +2,7 @@
 #define __POINTSIFT__HH___API
 #include <string>
 #include "pointSIFT_API.h"
-#include "../error.h"
+#include "../error_code/error_code.h"
 #include <pcl/point_types.h>
 #include <pcl/common/common.h>
 
@@ -16,13 +16,13 @@ class Point_sift_segmentation : public PointSifter
 public:
 	Point_sift_segmentation(int point_size,int cls,float freq,pcl::PointXYZ minp,pcl::PointXYZ maxp);
     //设置要识别的点云区域
-    ERROR_CODE set_region(pcl::PointXYZ minp, pcl::PointXYZ maxp);
+    Error_manager set_region(pcl::PointXYZ minp, pcl::PointXYZ maxp);
     //初始化网络, 加载网络权重
-	virtual ERROR_CODE init(std::string graph,std::string cpkt);
+	virtual Error_manager init(std::string graph,std::string cpkt);
 	//分割函数,输入点云,输出各类的点云,并保存中间文件方便查看识别结果.
 	//cloud:输入点云
 	//clouds:输出分类好的多个点云(附带颜色,红色为杂物,绿色为车,白色为地面)
-	virtual ERROR_CODE seg(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
+	virtual Error_manager seg(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 	    std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& clouds, std::string save_dir);
 
 	virtual ~Point_sift_segmentation();

+ 3 - 3
main.cpp

@@ -33,12 +33,12 @@ bool read_proto_param(std::string path, ::google::protobuf::Message& param)
 
 int main(int argc,char* argv[])
 {
-    ERROR_CODE code;
+    Error_manager code;
     //第一步,读取各个模块的配置
     //读取laser配置,根据配置创建laser
 
     //读取locate配置
-    Locate::LocateParameter locater_parameter;
+    Measure::LocateParameter locater_parameter;
     if(!read_proto_param("",locater_parameter))
     {
         LOG(ERROR)<<"read locate parameter failed";
@@ -60,7 +60,7 @@ int main(int argc,char* argv[])
     code=p_locater->init(locater_parameter);
     if(code!=SUCCESS)
     {
-        LOG(ERROR)<<"locater init failed code:"<<code;
+        LOG(ERROR)<<"locater init failed code:"<<code.to_string();
         return -1;
     }
     //创建terminor

+ 20 - 20
plc/plc_communicator.cpp

@@ -10,7 +10,7 @@ Plc_Communicator::Plc_Communicator(const char *ip, int port, int slave_id) : b_p
     m_plc_ip = ip;
     m_plc_port = port;
     m_plc_slave_id = slave_id;
-    m_plc_current_error = ERROR_CODE::SUCCESS;
+    m_plc_current_error =  SUCCESS;
     m_plc_status_update_timeout = 10000;
     for (size_t i = 0; i < PLC_REGION_NUM; i++)
     {
@@ -39,7 +39,7 @@ Plc_Communicator::~Plc_Communicator()
     disconnect();
 }
 
-ERROR_CODE Plc_Communicator::get_error()
+Error_manager Plc_Communicator::get_error()
 {
     return SUCCESS;
 }
@@ -55,22 +55,22 @@ bool Plc_Communicator::get_initialize_status()
     return b_plc_initialized;
 }
 
-ERROR_CODE Plc_Communicator::set_plc_callback(Command_Callback callback, void *p_owner)
+Error_manager Plc_Communicator::set_plc_callback(Command_Callback callback, void *p_owner)
 {
     if (callback == 0 || p_owner == 0)
-        return ERROR_CODE::PLC_SET_CALLBACK_ERROR;
+        return  PLC_SET_CALLBACK_ERROR;
     m_plc_callback = callback;
     p_plc_owner = p_owner;
-    return ERROR_CODE::SUCCESS;
+    return  SUCCESS;
 }
 
-ERROR_CODE Plc_Communicator::set_status_update_timeout(int millisecond){
+Error_manager Plc_Communicator::set_status_update_timeout(int millisecond){
     m_plc_status_update_timeout = millisecond;
-    return ERROR_CODE::SUCCESS;
+    return  SUCCESS;
 }
 
 // ××××××××××× 内部调用连接与重连 ×××××××××××
-ERROR_CODE Plc_Communicator::connect()
+Error_manager Plc_Communicator::connect()
 {
     std::lock_guard<std::mutex> lck(m_plc_mutex);
     int rc = m_plc_wrapper.initialize(m_plc_ip.c_str(), m_plc_port, m_plc_slave_id);
@@ -78,23 +78,23 @@ ERROR_CODE Plc_Communicator::connect()
     {
     case 0:
         b_plc_is_connected = true;
-        return ERROR_CODE::SUCCESS;
+        return  SUCCESS;
     case -1:
         b_plc_is_connected = false;
-        return ERROR_CODE::PLC_CONNECTION_FAILED;
+        return  PLC_CONNECTION_FAILED;
     case -2:
         b_plc_is_connected = false;
-        return ERROR_CODE::PLC_SLAVE_ID_ERROR;
+        return  PLC_SLAVE_ID_ERROR;
     case -3:
         b_plc_is_connected = false;
-        return ERROR_CODE::PLC_IP_PORT_ERROR;
+        return  PLC_IP_PORT_ERROR;
     default:
         b_plc_is_connected = false;
-        return ERROR_CODE::PLC_UNKNOWN_ERROR;
+        return  PLC_UNKNOWN_ERROR;
     }
 }
 
-ERROR_CODE Plc_Communicator::disconnect()
+Error_manager Plc_Communicator::disconnect()
 {
     std::lock_guard<std::mutex> lck(m_plc_mutex);
     m_plc_wrapper.deinitialize();
@@ -102,12 +102,12 @@ ERROR_CODE Plc_Communicator::disconnect()
 }
 
 // ××××××××××× 外部调用执行任务单 ×××××××××××
-ERROR_CODE Plc_Communicator::execute_task(Task_Base *task)
+Error_manager Plc_Communicator::execute_task(Task_Base *task)
 {
 }
 
 // ××××××××××× 外部调用获取数据, 终端id[1-6] ×××××××××××
-ERROR_CODE Plc_Communicator::get_plc_data(std::vector<uint16_t> &plc_data, int terminal_id)
+Error_manager Plc_Communicator::get_plc_data(std::vector<uint16_t> &plc_data, int terminal_id)
 {
     std::lock_guard<std::mutex> lck(m_plc_mutex);
     plc_data.clear();
@@ -121,10 +121,10 @@ ERROR_CODE Plc_Communicator::get_plc_data(std::vector<uint16_t> &plc_data, int t
         {
             plc_data.push_back(m_plc_data[i]);
         }
-        return ERROR_CODE::SUCCESS;
+        return  SUCCESS;
     }
     else
-        return ERROR_CODE::PLC_NOT_ENOUGH_DATA_ERROR;
+        return  PLC_NOT_ENOUGH_DATA_ERROR;
 }
 
 // ××××××××××× 更新线程静态函数 ×××××××××××
@@ -169,7 +169,7 @@ void Plc_Communicator::plc_update_thread(Plc_Communicator *plc_communicator)
                     }
                 }
             }else{
-                plc_communicator->m_plc_current_error = ERROR_CODE::PLC_READ_FAILED;
+                plc_communicator->m_plc_current_error =  PLC_READ_FAILED;
             }
             plc_communicator->m_plc_mutex.unlock();
 
@@ -232,7 +232,7 @@ void Plc_Communicator::plc_update_thread(Plc_Communicator *plc_communicator)
                     uint16_t value_temp = plc_communicator->m_plc_current_status[i].current_status;
                     int rc = plc_communicator->m_plc_wrapper.write_registers(address_temp, 1, &value_temp);
                     if(rc != 0)
-                        plc_communicator->m_plc_current_error = ERROR_CODE::PLC_WRITE_FAILED;
+                        plc_communicator->m_plc_current_error = PLC_WRITE_FAILED;
                     plc_communicator->m_plc_mutex.unlock();
                 }
             }

+ 10 - 10
plc/plc_communicator.h

@@ -9,7 +9,7 @@
 #include <unistd.h>
 #include <chrono>
 
-#include "../error.h"
+#include "../error_code/error_code.h"
 #include "../task/task_command_manager.h"
 #include "LibmodbusWrapper.h"
 #include "StdCondition.h"
@@ -30,7 +30,7 @@ const int PLC_LASER_HEIGHT_ADDR = 7;
 const int PLC_LASER_CORRECTNESS_ADDR = 8;
 const int PLC_LASER_WHEELBASE_ADDR = 9;
 
-typedef ERROR_CODE(*Command_Callback)(int terminal_id, void * p_owner);
+typedef Error_manager(*Command_Callback)(int terminal_id, void * p_owner);
 
 // plc通信类,modbus通信
 class Plc_Communicator
@@ -43,15 +43,15 @@ public:
     // get set 方法
     bool get_initialize_status();
     bool get_connection();
-    ERROR_CODE get_error();
+    Error_manager get_error();
     // 设置plc检测到指令后外部回调函数
-    ERROR_CODE set_plc_callback(Command_Callback callback, void * p_owner);
+    Error_manager set_plc_callback(Command_Callback callback, void * p_owner);
     // 执行任务单
-    ERROR_CODE execute_task(Task_Base* task);
+    Error_manager execute_task(Task_Base* task);
     // 获取实时数据
-    ERROR_CODE get_plc_data(std::vector<uint16_t> &plc_data,int terminal_id=-1);
+    Error_manager get_plc_data(std::vector<uint16_t> &plc_data,int terminal_id=-1);
     // 设置plc状态更新超时时间
-    ERROR_CODE set_status_update_timeout(int millisecond);
+    Error_manager set_status_update_timeout(int millisecond);
 
     struct plc_region_status{
         std::chrono::steady_clock::time_point last_time_point;
@@ -63,8 +63,8 @@ private:
     // 读写线程函数
     static void plc_update_thread(Plc_Communicator* plc_communicator);
     // 连接函数
-    ERROR_CODE connect();
-    ERROR_CODE disconnect();
+    Error_manager connect();
+    Error_manager disconnect();
 
 private:
     bool                b_plc_is_connected;     // 指示plc连接状态
@@ -84,7 +84,7 @@ private:
     int                 m_plc_status_update_timeout;    // plc状态更新超时时间
 
     std::vector<uint16_t>   m_plc_data;         // 从plc获取的实时数据
-    ERROR_CODE          m_plc_current_error;    // 当前plc出现的错误
+    Error_manager          m_plc_current_error;    // 当前plc出现的错误
     // 当前系统状态,实时更新到plc。状态254-255互换,状态1从收到指令开始,紧接着改为状态2,
     // 之后根据外部传入的task,决定写入3或4,默认3保留3秒,4持续保留直到新指令
     plc_region_status   m_plc_current_status[PLC_REGION_NUM];   

+ 1 - 1
plc/plc_task.cpp

@@ -21,6 +21,6 @@ int Plc_Task::init(){
     m_task_statu = Task_statu::TASK_CREATED;
 }
 
-ERROR_CODE Plc_Task::set_result(measure_result result){
+Error_manager Plc_Task::set_result(measure_result result){
     memcpy(&m_measure_result, &result, sizeof(result));
 }

+ 2 - 2
plc/plc_task.h

@@ -3,7 +3,7 @@
 #include <string.h>
 
 #include "../task/task_command_manager.h"
-#include "../error.h"
+#include "../error_code/error_code.h"
 
 class Plc_Task : public Task_Base
 {
@@ -23,7 +23,7 @@ public:
     };
     Plc_Task();
     ~Plc_Task();
-    ERROR_CODE set_result(measure_result result);
+    Error_manager set_result(measure_result result);
 
 private:
 struct measure_result m_measure_result;

+ 1 - 1
task/task_command_manager.h

@@ -5,7 +5,7 @@
 #ifndef TASK_COMAND_MANAGER_H
 #define TASK_COMAND_MANAGER_H
 #include <string>
-
+#include "../error_code/error_code.h"
 //任务类型
 enum Task_type
 {