Parcourir la source

hl20200525,代码以zzw_sift_wheel为基础,在雷达excute增加check_laser的判断.

huli il y a 5 ans
Parent
commit
fdc1eae7d7

+ 32 - 54
CMakeLists.txt

@@ -11,74 +11,52 @@ FIND_PACKAGE(PCL REQUIRED)
 FIND_PACKAGE(Protobuf REQUIRED)
 FIND_PACKAGE(Glog REQUIRED)
 set(CMAKE_MODULE_PATH "/usr/local/share/")
-
+set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wl,--no-as-needed")
 set(CMAKE_CXX_FLAGS "-std=c++11 -msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2")
-#set(CMAKE_BUILD_TYPE "RELEASE")
-set(CMAKE_BUILD_TYPE Debug)
+set(CMAKE_BUILD_TYPE "RELEASE")
+
 
 #find_package(Eigen3 REQUIRED)
 
 include_directories(
         laser
-#        plc
+        plc
         src
         Locate
-
-        error_code
-        tool
-        #        /usr/local/include/modbus
-        ${PCL_INCLUDE_DIRS}
-        ${OpenCV_INCLUDE_DIRS}
+        /usr/local/include
+        /usr/local/include/modbus
+        /usr/local/include/snap7
+  ${PCL_INCLUDE_DIRS}
+  ${OpenCV_INCLUDE_DIRS}
 )
 link_directories("/usr/local/lib")
 
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/task TASK_MANAGER_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/error_code ERROR_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/tool TOOL_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/laser LASER_SRC )
 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}/tool TOOL_SRC )
-
-
-add_executable(LidarMeasure ./main.cpp ./error_code/error_code.cpp
-#        ./src/StdCondition.cpp ./src/CalibParam.pb.cc
-        ./tool/StdCondition.cpp
-        ./globalmsg.pb.cc
-        ./MeasureTopicPublisher.cpp
-        ./laser/laser_task_command
-        ${LASER_SRC}
-#        ${PLC_SRC}
-#        ${TERMINOR_SRC}
-        ${LOCATE_SRC}
-        ${TASK_MANAGER_SRC}
-        ${TOOL_SRC}
-        ./tool/binary_buf.cpp
-        ./tool/thread_condition.h ./tool/thread_condition.cpp
-        ./tool/thread_safe_queue.h ./tool/thread_safe_queue.cpp
-        ./tool/singleton.h ./tool/singleton.cpp
-
-        )
-
-
-
-
-target_link_libraries(LidarMeasure
-        #${OpenCV_LIBS}
-        ${GLOG_LIBRARIES}
-        ${PCL_LIBRARIES}
-        ${PROTOBUF_LIBRARIES}
-#        ipopt
-        libtensorflow_cc.so
-        #tf_3dcnn_api.so
-        pointSIFT_API.so
-        #dark.so
-        /usr/local/lib/libglog.a
-        ##/usr/local/lib/libmodbus.so
-        /usr/local/lib/libgflags.a
-        /usr/local/lib/liblivox_sdk_static.a
-        /usr/local/apr/lib/libapr-1.a
-        nnxx
-        nanomsg
-        )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/verify VERIFY_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/system_manager SYS_SRC )
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/wj_lidar WJLIDAR_SRC )
+
+
+# plc test module
+add_executable(plc_test  ./test/plc_test.cpp ${PLC_SRC} ${TASK_MANAGER_SRC} ${TOOL_SRC} ${ERROR_CODE_SRC})
+target_link_libraries(plc_test ${OpenCV_LIBS}
+        ${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ipopt modbus libnanomsg.so libnnxx.a libglog.a libgflags.a)
+add_executable(fence_debug  test/plc_s7.cpp wj_lidar/wj_lidar_msg.pb.cc)
+target_link_libraries(fence_debug ${GLOG_LIBRARIES} ${PROTOBUF_LIBRARIES} /usr/local/lib/libglog.a
+        /usr/local/lib/libgflags.a nnxx nanomsg)
+
+
+add_executable(locate  main.cpp ${LOCATE_SRC} ${PLC_SRC} ${TERMINOR_SRC} ${TASK_MANAGER_SRC} ${LASER_SRC} ${ERROR_SRC}
+        ${TOOL_SRC} ${SYS_SRC} ${VERIFY_SRC} ${WJLIDAR_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 snap7 nnxx nanomsg)
 
 

+ 0 - 6
error_code/error_code.cpp

@@ -156,12 +156,6 @@ bool Error_manager::operator!=(Error_code error_code)
         return false;
     }
 }
-//重载<<,支持cout<<
-std::ostream & operator<<(std::ostream &out, Error_manager &error_manager)
-{
-	out << error_manager.to_string();
-	return out;
-}
 
 //获取错误码
 Error_code Error_manager::get_error_code()

+ 4 - 18
error_code/error_code.h

@@ -12,7 +12,6 @@
 
 #include <string>
 #include <string.h>
-#include<iostream>
 
 //错误管理类转化为字符串 的前缀,固定长度为58
 //这个是由显示格式来确定的,如果要修改格式或者 Error_code长度超过8位,Error_level长度超过2位,折需要重新计算
@@ -65,7 +64,7 @@ enum Error_code
 //    错误码的规范,
 //    错误码是int型,32位,十六进制。
 //    例如0x12345678
-//    12表示功能模块,例如:laser雷达模块               	框架制定
+//    12表示功能模块,例如:laser雷达模块               框架制定
 //    34表示文件名称,例如:laser_livox.cpp             框架制定
 //    56表示具体的类,例如:class laser_livox           个人制定
 //    78表示类的函数,例如:laser_livox::start();       个人制定
@@ -74,6 +73,7 @@ enum Error_code
 
 //    laser扫描模块
     LASER_ERROR_BASE                = 0x01000000,
+
 //    laser_base基类
 	LASER_BASE_ERROR_BASE			= 0x01010000,
     LASER_TASK_PARAMETER_ERROR      = 0x01010001,   //雷达任务输入参数错误
@@ -81,9 +81,9 @@ enum Error_code
 	LASER_START_FAILED,
 	LASER_CHECK_FAILED				,
 	LASER_STATUS_ERROR,								//雷达状态错误
-	//laser livox
+
+
     LASER_LIVOX_SKD_INIT_FAILED,
-	LASER_TASK_OVER_TIME,							//雷达模块,任务超时
 
 
 //    laser_livox.cpp的错误码
@@ -91,15 +91,6 @@ enum Error_code
     LIVOX_START_FAILE               = 0x01020101,
 	LIVOX_TASK_TYPE_ERROR,							//livox任务类型错误
 
-	//laser_manager 雷达管理模块
-	LASER_MANAGER_ERROR_BASE						= 0x01030000,
-	LASER_MANAGER_READ_PROTOBUF_ERROR,				//雷达管理模块,读取参数错误
-	LASER_MANAGER_IS_NOT_READY,						//雷达管理模块,不在准备状态
-	LASER_MANAGER_LASER_INDEX_ERRPR,				//雷达管理模块,雷达索引错误,编号错误。
-	LASER_MANAGER_TASK_OVER_TIME,					//雷达管理模块,任务超时
-
-
-
 
      //PLC error code  ...
     PLC_ERROR_BASE                  = 0x02010000,
@@ -223,9 +214,6 @@ enum Error_code
 
 
 
-    //task module,  error from 0x10010000-0x1001FFFF
-	TASK_MODULE_ERROR_BASE 							= 0x10010000,
-	TASK_TYPE_IS_UNKNOW,
 };
 
 //错误等级,用来做故障处理
@@ -312,8 +300,6 @@ public://外部接口函数
     bool operator!=(const Error_manager & error_manager);
     //重载!=,支持Error_manager和Error_code的直接比较
     bool operator!=(Error_code error_code);
-	//重载<<,支持cout<<
-	friend std::ostream & operator<<(std::ostream &out, Error_manager &error_manager);
 
 
     //获取错误码

+ 12 - 32
laser/Laser.cpp

@@ -145,7 +145,7 @@ Error_manager Laser_base::execute_task(Task_Base* p_laser_task)
 	}
 }
 //检查雷达状态,是否正常运行
-Error_manager Laser_base::check_status()
+Error_manager Laser_base::check_laser()
 {
 	if ( is_ready() )
 	{
@@ -160,17 +160,15 @@ Error_manager Laser_base::start_scan()
 	LOG(INFO) << " Laser_base::start_scan "<< this;
 	if ( is_ready() )
 	{
-		//重置数据
-		m_points_count=0;
-		m_queue_laser_data.clear_and_delete();
-		m_last_data.clear();
-
 		//启动雷达扫描
 		m_laser_scan_flag=true;				//启动雷达扫描
 		m_laser_statu = LASER_BUSY;			//雷达状态 繁忙
 		m_condition_receive.notify_all(true);		//唤醒接受线程
 		m_condition_transform.notify_all(true);	//唤醒转化线程
-
+		//重置数据
+		m_points_count=0;
+		m_queue_laser_data.clear_and_delete();
+		m_last_data.clear();
 		return Error_code::SUCCESS;
 	}
 	else
@@ -206,7 +204,7 @@ Error_manager Laser_base::end_task()
 	if(mp_laser_task !=NULL)
 	{
 		//判断任务单的错误等级,
-		if ( mp_laser_task->get_task_error_manager().get_error_level() < Error_level::MINOR_ERROR)
+		if ( mp_laser_task->get_task_error_manager().get_error_level() > Error_level::MINOR_ERROR)
 		{
 			if ( m_laser_statu == LASER_BUSY )
 			{
@@ -226,14 +224,7 @@ Error_manager Laser_base::end_task()
 	return Error_code::SUCCESS;
 }
 
-//取消任务单,
-Error_manager Laser_base::cancel_task()
-{
-	end_task();
-	//强制改为TASK_OVER,不管它当前在做什么。
-	mp_laser_task->set_task_statu(TASK_DEAD);
-	return Error_code::SUCCESS;
-}
+
 
 //设置保存文件的路径,并打开文件,
 Error_manager Laser_base::set_open_save_path(std::string save_path,bool is_save)
@@ -248,27 +239,15 @@ Error_manager Laser_base::set_open_save_path(std::string save_path,bool is_save)
 	}
 	else
 	{
-		time_t nowTime;
-		nowTime = time(NULL);
-		struct tm* sysTime = localtime(&nowTime);
-		char time_string[256] = { 0 };
-		sprintf(time_string, "%04d%02d%02d_%02d%02d%02d",
-				sysTime->tm_year + 1900, sysTime->tm_mon + 1, sysTime->tm_mday, sysTime->tm_hour, sysTime->tm_min, sysTime->tm_sec);
-
 		m_save_path = save_path;
 		char pts_file[255] = { 0 };
-//		sprintf(pts_file, "%s/pts%d.txt", save_path.c_str(), m_laser_id+1);
-		sprintf(pts_file, "%s/pst%s__%d.txt", save_path.c_str(), time_string,m_laser_id+1);
-		cout<<"pts_file " << pts_file <<endl;
+		sprintf(pts_file, "%s/pts%d.txt", save_path.c_str(), m_laser_id+1);
 		m_points_log_tool.open(pts_file);
 		std::cout << "huli m_points_log_tool path "<< pts_file << std::endl;
 
 		char bin_file[255] = { 0 };
-//		sprintf(bin_file, "%s/laser%d.data", save_path.c_str(), m_laser_id+1);
-		sprintf(bin_file, "%s/laser%slaser%d.data", save_path.c_str(),time_string, m_laser_id+1);
+		sprintf(bin_file, "%s/laser%d.data", save_path.c_str(), m_laser_id+1);
 		m_binary_log_tool.open(bin_file,true);
-		std::cout << "huli m_binary_log_tool path "<< bin_file << std::endl;
-
 		return Error_code::SUCCESS;
 	}
 }
@@ -428,7 +407,7 @@ void Laser_base::thread_transform()
 							if ( t_error != Error_code::SUCCESS )
 							{
 								mp_laser_task->get_task_error_manager().compare_and_cover_error(t_error);
-								stop_scan();  //因错误而停止。
+								stop_scan();
 							}
 						}
 					}
@@ -437,7 +416,8 @@ void Laser_base::thread_transform()
 					//思科雷达停止扫描。
 					if (t_buf_type == BUF_STOP)
 					{
-						stop_scan();//注:这个只是思科的雷达停止处,不同的雷达在不同的地方调用 stop_scan
+						//注:这个只是思科的雷达停止处,不同的雷达在不同的地方调用 stop_scan
+						stop_scan();
 					}
 				}
 			}

+ 2 - 4
laser/Laser.h

@@ -63,15 +63,13 @@ public:
 	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
 	virtual Error_manager execute_task(Task_Base* p_laser_task);
 	//检查雷达状态,是否正常运行
-	virtual Error_manager check_status();
+	virtual Error_manager check_laser();
 	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
 	virtual Error_manager start_scan();
 	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
 	virtual Error_manager stop_scan();
 	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
 	virtual Error_manager end_task();
-	//取消任务单,
-	virtual Error_manager cancel_task();
 
 public:
 	//设置保存文件的路径,并打开文件,
@@ -119,7 +117,7 @@ protected:
 protected:
 	//为了保证多线程的数据安全,修改共享数据必须加锁。  atomic 和 安全队列 可以不加锁进行读写
 	//建议:判断标志位使用 atomic, 容器要封装并使用 安全容器,
-//	std::mutex          				m_laser_lock;            	//雷达数据锁
+	std::mutex          				m_laser_lock;            	//雷达数据锁
 
 	std::atomic<int>					m_laser_id;                 //雷达设备id
 	Laser_proto::laser_parameter  		m_laser_param;				//雷达的配置参数

+ 54 - 136
laser/LivoxLaser.cpp

@@ -57,66 +57,70 @@ Error_manager CLivoxLaser::execute_task(Task_Base* p_laser_task)
 	//检查指针
 	if (p_laser_task == NULL) {
 		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
-							 "Laser_base::execute_task failed, POINTER_IS_NULL");
+							 "Laser_base::porform_task failed, POINTER_IS_NULL");
 	}
 	//检查任务类型,
-	if (p_laser_task->get_task_type() != LASER_BASE_SCAN_TASK)
+	if (p_laser_task->get_task_type() != LASER_TASK)
 	{
 		return Error_manager(Error_code::LIVOX_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
-							 "laser task type error != LASER_BASE_SCAN_TASK");
+							 "laser task type error != LASER_TASK");
 	}
 
-	//接受任务,并将任务的状态改为TASK_SIGNED已签收
-	mp_laser_task = (Laser_task *) p_laser_task;
-	mp_laser_task->set_task_statu(TASK_SIGNED);
-
-	//检查消息内容是否正确,
-	//检查三维点云指针
-	if (mp_laser_task->get_task_point_cloud().get() == NULL)
-	{
-		t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
-											Error_level::MINOR_ERROR,
-											"execute_task mp_task_point_cloud is null");
-		//将任务的状态改为 TASK_ERROR 结束错误
-		mp_laser_task->set_task_statu(TASK_ERROR);
-		//返回错误码
-		mp_laser_task->set_task_error_manager(t_result);
-		return t_result;
-	}
-	else
+	//检查雷达状态
+	t_error = check_laser();
+	if ( t_error == SUCCESS )
 	{
-		m_frame_maxnum=mp_laser_task->get_task_frame_maxnum();
+		//接受任务,并将任务的状态改为TASK_SIGNED已签收
+		mp_laser_task = (Laser_task *) p_laser_task;
+		mp_laser_task->set_task_statu(TASK_SIGNED);
 
-		//设置保存文件的路径
-		t_error = set_open_save_path(mp_laser_task->get_task_save_path(),mp_laser_task->get_task_save_flag());
-		if ( t_error != Error_code::SUCCESS )
+		//检查消息内容是否正确,
+		//检查三维点云指针
+		if (mp_laser_task->get_task_point_cloud().get() == NULL)
 		{
-			//文件保存文件的路径的设置 允许失败。继续后面的动作
+			t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
+										 Error_level::MINOR_ERROR,
+										 "execute_task mp_task_point_cloud is null");
 			t_result.compare_and_cover_error(t_error);
 		}
-		//启动雷达扫描
-		t_error = start_scan();
-		if ( t_error != Error_code::SUCCESS )
+		else if (mp_laser_task->get_task_cloud_lock() == NULL)
 		{
+			t_error.error_manager_reset(Error_code::POINTER_IS_NULL,
+										Error_level::MINOR_ERROR,
+										"execute_task mp_task_cloud_lock is null");
 			t_result.compare_and_cover_error(t_error);
-
-			//将任务的状态改为 TASK_OVER 结束任务
-			mp_laser_task->set_task_statu(TASK_OVER);
-			//返回错误码
-			mp_laser_task->set_task_error_manager(t_result);
-			return t_result;
 		}
 		else
 		{
-			//将任务的状态改为 TASK_WORKING 处理中
-			mp_laser_task->set_task_statu(TASK_WORKING);
+			m_frame_maxnum=mp_laser_task->get_task_frame_maxnum();
+
+			//设置保存文件的路径
+			std::string save_path = mp_laser_task->get_task_save_path();
+			t_error = set_open_save_path(save_path,m_laser_param.is_save_txt());
+			if ( t_error != Error_code::SUCCESS )
+			{
+				//文件保存文件的路径的设置 允许失败。继续后面的动作
+				t_result.compare_and_cover_error(t_error);
+			}
+			//启动雷达扫描
+			t_error = start_scan();
+			if ( t_error != Error_code::SUCCESS )
+			{
+				t_result.compare_and_cover_error(t_error);
+			}
+			else
+			{
+				//将任务的状态改为 TASK_WORKING 处理中
+				mp_laser_task->set_task_statu(TASK_WORKING);
+			}
 		}
 	}
+
 	//返回错误码
 	if (t_result != Error_code::SUCCESS)
 	{
-		//将任务的状态改为 TASK_ERROR 结束错误
-		mp_laser_task->set_task_statu(TASK_ERROR);
+		//将任务的状态改为 TASK_OVER 结束任务
+		mp_laser_task->set_task_statu(TASK_OVER);
 		//返回错误码
 		mp_laser_task->set_task_error_manager(t_result);
 		return t_result;
@@ -125,9 +129,18 @@ Error_manager CLivoxLaser::execute_task(Task_Base* p_laser_task)
 }
 
 //检查雷达状态,是否正常运行
-Error_manager CLivoxLaser::check_status()
+Error_manager CLivoxLaser::check_laser()
 {
-	return Laser_base::check_status();
+	if ( is_ready() )
+	{
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::lIVOX_STATUS_ERROR, Error_level::MINOR_ERROR,
+							 " CLivoxLaser::check_status error ");
+	}
+	return Error_code::SUCCESS;
 }
 //雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
 Error_manager CLivoxLaser::start_scan()
@@ -239,8 +252,6 @@ void CLivoxLaser::InitLivox()
 			SetBroadcastCallback(OnDeviceBroadcast);
 			SetDeviceStateUpdateCallback(OnDeviceChange);
 			g_init = true;
-
-
 		}
 	}
 }
@@ -321,27 +332,6 @@ void CLivoxLaser::OnDeviceChange(const DeviceInfo *info, DeviceEvent type)
 			}
 			g_devices[handle].device_state = kDeviceStateSampling;
 		}
-
-		CLivoxLaser* tp_livox = g_all_laser[handle];
-		if (tp_livox == NULL)
-		{
-			if (g_handle_sn.find(handle) != g_handle_sn.end())
-			{
-				std::string sn = g_handle_sn[handle];
-				if (g_sn_laser.find(sn) != g_sn_laser.end())
-				{
-					tp_livox = g_sn_laser[sn];
-					g_all_laser[handle] = tp_livox;
-					if (tp_livox)
-						tp_livox->UpdataHandle();
-				}
-			}
-		}
-
-		//获取欧拉角
-		uint8_t temp =  LidarGetExtrinsicParameter(handle, lidar_get_extrinsic_parameter_callback, NULL);
-//		uint8_t temp =  LidarSetExtrinsicParameter( handle,	&(tp_livox->m_set_extrinsic_parameter), common_command_callback, NULL);
-
 	}
 }
 void CLivoxLaser::OnDeviceBroadcast(const BroadcastDeviceInfo *info)
@@ -373,8 +363,6 @@ void CLivoxLaser::OnDeviceBroadcast(const BroadcastDeviceInfo *info)
 		else
 			g_sn_handle.insert(std::make_pair(sn,handle));
 
-
-
 	}
 
 }
@@ -449,73 +437,3 @@ void CLivoxLaser::LidarDataCallback(uint8_t handle, LivoxEthPacket *data, uint32
 		std::cout << "huli 2z error " << "livox = "<< livox  << std::endl;
 	}
 }
-
-//获取欧拉角。使用 LidarGetExtrinsicParameter 来设置回调函数。
-void CLivoxLaser::lidar_get_extrinsic_parameter_callback(uint8_t status,
-											uint8_t handle,
-											LidarGetExtrinsicParameterResponse *response,
-											void *client_data)
-{
-	std::cout << "-----------------lidar_get_extrinsic_parameter_callback-------------------" << std::endl;
-
-	//m_extrinsic_parameter;		//欧拉角,(roll, pitch, yaw, x, y, z)
-	std::cout << "roll = " << response->roll << std::endl;
-	std::cout << "pitch = " << response->pitch << std::endl;
-	std::cout << "yaw = " << response->yaw << std::endl;
-
-	std::cout << "x = " << response->x << std::endl;
-	std::cout << "y = " << response->y << std::endl;
-	std::cout << "z = " << response->z << std::endl;
-
-	CLivoxLaser* tp_livox = g_all_laser[handle];
-	if (tp_livox == NULL)
-	{
-		if (g_handle_sn.find(handle) != g_handle_sn.end())
-		{
-			std::string sn = g_handle_sn[handle];
-			if (g_sn_laser.find(sn) != g_sn_laser.end())
-			{
-				tp_livox = g_sn_laser[sn];
-				g_all_laser[handle] = tp_livox;
-				if (tp_livox)
-					tp_livox->UpdataHandle();
-			}
-		}
-	}
-	tp_livox->m_get_extrinsic_parameter = *response;
-
-	double t_pitch = tp_livox->m_get_extrinsic_parameter.pitch;
-	double t_roll = tp_livox->m_get_extrinsic_parameter.roll;
-	double t_yaw = tp_livox->m_get_extrinsic_parameter.yaw;
-	double t_x = tp_livox->m_get_extrinsic_parameter.x;
-	double t_y = tp_livox->m_get_extrinsic_parameter.y;
-	double t_z = tp_livox->m_get_extrinsic_parameter.z;
-
-	//欧拉角转化为3*4矩阵
-	t_roll = t_roll * M_PI / 180.0;
-	t_pitch = t_pitch * M_PI / 180.0;
-	t_yaw = t_yaw * M_PI / 180.0;
-	double rotate[12] = {
-	std::cos(t_pitch) * std::cos(t_yaw),
-	std::sin(t_roll) * std::sin(t_pitch) * std::cos(t_yaw) - std::cos(t_roll) * std::sin(t_yaw),
-	std::cos(t_roll) * std::sin(t_pitch) * std::cos(t_yaw) + std::sin(t_roll) * std::sin(t_yaw),
-	t_x,
-	std::cos(t_pitch) * std::sin(t_yaw),
-	std::sin(t_roll) * std::sin(t_pitch) * std::sin(t_yaw) + std::cos(t_roll) * std::cos(t_yaw),
-	std::cos(t_roll) * std::sin(t_pitch) * std::sin(t_yaw) - std::sin(t_roll) * std::cos(t_yaw),
-	t_y,
-	-std::sin(t_pitch),
-	std::sin(t_roll) * std::cos(t_pitch),
-	std::cos(t_roll) * std::cos(t_pitch),
-	t_z
-	};
-
-	tp_livox->set_laser_matrix(rotate, 12);
-
-}
-
-void CLivoxLaser::common_command_callback(uint8_t status, uint8_t handle, uint8_t response, void *client_data)
-{
-	std::cout << "-----------------common_command_callback-------------------" << std::endl;
-
-}

+ 1 - 11
laser/LivoxLaser.h

@@ -45,7 +45,7 @@ public:
 	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
 	virtual Error_manager execute_task(Task_Base* p_laser_task);
 	//检查雷达状态,是否正常运行
-	virtual Error_manager check_status();
+	virtual Error_manager check_laser();
 	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
 	virtual Error_manager start_scan();
 	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
@@ -76,14 +76,6 @@ protected:
 	static void OnDeviceBroadcast(const BroadcastDeviceInfo *info);
 	static void OnSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data);
 
-	//获取欧拉角。使用 LidarGetExtrinsicParameter 来设置回调函数。
-	static void lidar_get_extrinsic_parameter_callback(uint8_t status,
-											   uint8_t handle,
-											   LidarGetExtrinsicParameterResponse *response,
-											   void *client_data);
-
-	static void common_command_callback(uint8_t status, uint8_t handle, uint8_t response, void *client_data);
-
 protected:
 	uint8_t									m_handle;
 	unsigned int							m_frame_maxnum;
@@ -98,8 +90,6 @@ protected:
 	static unsigned int						g_count[kMaxLidarCount];
 
 
-	LidarGetExtrinsicParameterResponse 		m_get_extrinsic_parameter;		//欧拉角,(roll, pitch, yaw, x, y, z)
-	LidarSetExtrinsicParameterRequest		m_set_extrinsic_parameter;		//欧拉角,(roll, pitch, yaw, x, y, z)
 };
 
 #endif

+ 0 - 228
laser/LivoxMid100Laser.cpp

@@ -1,228 +0,0 @@
-
-#include "LivoxMid100Laser.h"
-#include <glog/logging.h>
-RegisterLaser(LivoxMid100)
-
-
-CLivoxMid100Laser::CLivoxMid100Laser(int id, Laser_proto::laser_parameter laser_param)
-:CLivoxLaser(id, laser_param)
-{
-	//设备livox扫描最大帧数
-    m_frame_maxnum = laser_param.frame_num();
-	//判断参数类型,
-    if (laser_param.type() == "LivoxMid100")
-    {
-        std::string sn = laser_param.sn();
-        std::string sn1 = sn, sn2 = sn, sn3 = sn;
-        sn1 += "1";
-        sn2 += "2";
-        sn3 += "3";
-        g_sn_laser.insert(std::make_pair(sn1, this));
-        g_sn_laser.insert(std::make_pair(sn2, this));
-        g_sn_laser.insert(std::make_pair(sn3, this));
-		//初始化livox
-		InitLivox();
-    }
-}
-CLivoxMid100Laser::~CLivoxMid100Laser()
-{
-
-}
-
-//雷达链接设备,为3个线程添加线程执行函数。
-Error_manager CLivoxMid100Laser::connect_laser()
-{
-	Error_manager t_error;
-	//设置点云变换矩阵
-	double matrix[12]={0};
-	matrix[0]=m_laser_param.mat_r00();
-	matrix[1]=m_laser_param.mat_r01();
-	matrix[2]=m_laser_param.mat_r02();
-	matrix[3]=m_laser_param.mat_r03();
-
-	matrix[4]=m_laser_param.mat_r10();
-	matrix[5]=m_laser_param.mat_r11();
-	matrix[6]=m_laser_param.mat_r12();
-	matrix[7]=m_laser_param.mat_r13();
-
-	matrix[8]=m_laser_param.mat_r20();
-	matrix[9]=m_laser_param.mat_r21();
-	matrix[10]=m_laser_param.mat_r22();
-	matrix[11]=m_laser_param.mat_r23();
-	t_error = set_laser_matrix(matrix, 12);
-	if ( t_error != Error_code::SUCCESS )
-	{
-		return t_error;
-	}
-	return CLivoxLaser::connect_laser();
-}
-//雷达断开链接,释放3个线程
-Error_manager CLivoxMid100Laser::disconnect_laser()
-{
-	return CLivoxLaser::disconnect_laser();
-}
-
-
-
-//对外的接口函数,负责接受并处理任务单,
-//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-Error_manager CLivoxMid100Laser::execute_task(Task_Base* p_laser_task)
-{
-	LOG(INFO) << " CLivoxMid100Laser::execute_task start  "<< this;
-	Error_manager t_error;
-	Error_manager t_result;
-
-	//检查指针
-	if (p_laser_task == NULL) {
-		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
-							 "Laser_base::porform_task failed, POINTER_IS_NULL");
-	}
-	//检查任务类型,
-	if (p_laser_task->get_task_type() != LASER_BASE_SCAN_TASK)
-	{
-		return Error_manager(Error_code::LIVOX_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
-							 "laser task type error != LASER_BASE_SCAN_TASK");
-	}
-
-	//接受任务,并将任务的状态改为TASK_SIGNED已签收
-	mp_laser_task = (Laser_task *) p_laser_task;
-	mp_laser_task->set_task_statu(TASK_SIGNED);
-
-	//检查消息内容是否正确,
-	//检查三维点云指针
-	if (mp_laser_task->get_task_point_cloud().get() == NULL)
-	{
-		t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
-									 Error_level::MINOR_ERROR,
-									 "execute_task mp_task_point_cloud is null");
-		//将任务的状态改为 TASK_OVER 结束任务
-		mp_laser_task->set_task_statu(TASK_OVER);
-		//返回错误码
-		mp_laser_task->set_task_error_manager(t_result);
-		return t_result;
-	}
-	else
-	{
-		m_frame_maxnum=mp_laser_task->get_task_frame_maxnum();
-
-
-		//设置保存文件的路径
-		std::string save_path = mp_laser_task->get_task_save_path();
-		t_error = set_open_save_path(save_path);
-		if ( t_error != Error_code::SUCCESS )
-		{
-			//文件保存文件的路径的设置 允许失败。继续后面的动作
-			t_result.compare_and_cover_error(t_error);
-		}
-		//启动雷达扫描
-		t_error = start_scan();
-		if ( t_error != Error_code::SUCCESS )
-		{
-			t_result.compare_and_cover_error(t_error);
-
-			//将任务的状态改为 TASK_OVER 结束任务
-			mp_laser_task->set_task_statu(TASK_OVER);
-			//返回错误码
-			mp_laser_task->set_task_error_manager(t_result);
-			return t_result;
-		}
-		else
-		{
-			//将任务的状态改为 TASK_WORKING 处理中
-			mp_laser_task->set_task_statu(TASK_WORKING);
-		}
-	}
-	//返回错误码
-	if (t_result != Error_code::SUCCESS)
-	{
-		mp_laser_task->set_task_error_manager(t_result);
-	}
-	return t_result;
-}
-
-//检查雷达状态,是否正常运行
-Error_manager CLivoxMid100Laser::check_status()
-{
-	return CLivoxLaser::check_status();
-}
-
-//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-Error_manager CLivoxMid100Laser::start_scan()
-{
-	LOG(INFO) << " livoxMid100 start :" << m_laser_param.sn();
-	//清空livox子类的队列,
-	m_queue_livox_data.clear_and_delete();
-	g_count[m_handle1] = 0;
-	g_count[m_handle2] = 0;
-	g_count[m_handle3] = 0;
-	return CLivoxLaser::start_scan();
-}
-//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-Error_manager CLivoxMid100Laser::stop_scan()
-{
-	LOG(INFO)<<" livoxmid100 stoped !!!"<<m_laser_param.sn();
-	return CLivoxLaser::stop_scan();
-}
-//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-Error_manager CLivoxMid100Laser::end_task()
-{
-	return CLivoxLaser::end_task();
-}
-//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
-//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
-bool CLivoxMid100Laser::is_ready()
-{
-	//3个livox雷达设备的状态,livox sdk后台线程的状态
-	bool cond1=g_devices[m_handle1].device_state == kDeviceStateConnect ||
-			   g_devices[m_handle1].device_state == kDeviceStateSampling;
-	bool cond2=g_devices[m_handle2].device_state == kDeviceStateConnect ||
-			   g_devices[m_handle2].device_state == kDeviceStateSampling;
-	bool cond3=g_devices[m_handle3].device_state == kDeviceStateConnect ||
-			   g_devices[m_handle3].device_state == kDeviceStateSampling;
-
-	if ( cond1 && cond2 && cond3 && m_laser_statu == LASER_READY )
-	{
-		true;
-	}
-	else
-	{
-		false;
-	}
-}
-
-
-void CLivoxMid100Laser::UpdataHandle()
-{
-	std::string sn = m_laser_param.sn();
-	std::string sn1 = sn, sn2 = sn, sn3 = sn;
-	sn1 += "1";
-	sn2 += "2";
-	sn3 += "3";
-	if (g_sn_handle.find(sn1) != g_sn_handle.end())
-	{
-		m_handle1 = g_sn_handle[sn1];
-	}
-	if (g_sn_handle.find(sn2) != g_sn_handle.end())
-	{
-		m_handle2 = g_sn_handle[sn2];
-	}
-	if (g_sn_handle.find(sn3) != g_sn_handle.end())
-	{
-		m_handle3 = g_sn_handle[sn3];
-	}
-}
-bool CLivoxMid100Laser::IsScanComplete()
-{
-	//雷达的采集帧数判断,直接比较任务单里面的帧数最大值
-	if(mp_laser_task==NULL)
-	{
-		return false;
-	}
-	else
-	{
-		int frame_count=mp_laser_task->get_task_frame_maxnum();
-		return g_count[m_handle1] >= frame_count && g_count[m_handle2] >= frame_count
-			   && g_count[m_handle2] >= frame_count;
-	}
-}

+ 0 - 46
laser/LivoxMid100Laser.h

@@ -1,46 +0,0 @@
-#pragma once
-#include "LivoxLaser.h"
-#include "livox_def.h"
-#include "livox_sdk.h"
-#include <map>
-class CLivoxMid100Laser : public CLivoxLaser
-{
-
-public:
-	CLivoxMid100Laser(int id, Laser_proto::laser_parameter laser_param);
-	~CLivoxMid100Laser();
-
-	//雷达链接设备,为3个线程添加线程执行函数。
-	virtual Error_manager connect_laser();
-	//雷达断开链接,释放3个线程
-	virtual Error_manager disconnect_laser();
-	//对外的接口函数,负责接受并处理任务单,
-	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-	virtual Error_manager execute_task(Task_Base* p_laser_task);
-	//检查雷达状态,是否正常运行
-	virtual Error_manager check_status();
-	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-	virtual Error_manager start_scan();
-	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-	virtual Error_manager stop_scan();
-	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-	virtual Error_manager end_task();
-
-	//判断雷达状态是否为待机,如果已经准备好,则可以执行任务。
-	//子类重载 is_ready(),里面增加livox sdk后台线程状态的判断。
-	virtual bool is_ready();
-
-
-protected:
-	virtual bool IsScanComplete();
-	virtual void UpdataHandle();
-
-
-protected:
-	uint8_t		m_handle1;
-	uint8_t		m_handle2;
-	uint8_t		m_handle3;
-};
-
-

+ 0 - 323
laser/Sick511FileLaser.cpp

@@ -1,323 +0,0 @@
-
-#include "Sick511FileLaser.h"
-#include <unistd.h>
-
-RegisterLaser(Sick511File);
-CSick511FileLaser::CSick511FileLaser(int id, Laser_proto::laser_parameter laser_param)
-:Laser_base(id, laser_param)
-,m_start_read(false)
-{
-}
-
-CSick511FileLaser::~CSick511FileLaser()
-{
-	if (m_stream_read.is_open())
-		m_stream_read.close();
-}
-
-
-
-//雷达链接设备,为3个线程添加线程执行函数。
-Error_manager CSick511FileLaser::connect_laser()
-{
-	std::string ip = m_laser_param.laser_ip();
-	char file[255] = { 0 };
-	sprintf(file, "%s/laser%d.data", ip.c_str(), m_laser_id + 1);
-	if (m_stream_read.is_open())
-	{
-		m_stream_read.close();
-	}
-	m_stream_read.open(file, ios::in | ios::binary);
-	if (!m_stream_read.good())
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							 "m_stream_read.open error ");
-	m_laser_statu = LASER_READY;
-	m_file = file;
-	return Laser_base::connect_laser();
-}
-//雷达断开链接,释放3个线程
-Error_manager CSick511FileLaser::disconnect_laser()
-{
-	if(m_stream_read.is_open())
-		m_stream_read.close();
-	return Laser_base::disconnect_laser();
-}
-//对外的接口函数,负责接受并处理任务单,
-//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-Error_manager CSick511FileLaser::execute_task(Task_Base* p_laser_task)
-{
-
-}
-//检查雷达状态,是否正常运行
-Error_manager CSick511FileLaser::check_laser()
-{
-
-}
-//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-Error_manager CSick511FileLaser::start_scan()
-{
-	std::lock_guard<std::mutex> lk(m_mutex);
-
-	if (!this->is_ready())
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							" is_ready error ");
-
-	m_start_read = true;
-	return Laser_base::start_scan();
-
-}
-//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-Error_manager CSick511FileLaser::stop_scan()
-{
-	std::lock_guard<std::mutex> lk(m_mutex);
-	m_start_read = false;
-	return Error_code::SUCCESS;
-}
-//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-Error_manager CSick511FileLaser::end_task()
-{
-
-}
-
-
-
-Buf_type CSick511FileLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
-{
-	////ƴ���ϴ�δ�������
-
-	Buf_type type = BUF_UNKNOW;
-	Binary_buf frame;
-
-	if (m_last_data.get_length() > 0)
-	{
-		if (pData)
-			frame = m_last_data + (*pData);
-		else
-			frame = m_last_data;
-		m_last_data = Binary_buf();
-	}
-	else if(pData)
-	{
-		frame = (*pData);
-	}
-	else
-	{
-		return type;
-	}
-
-	int head = FindHead(frame.get_buf(), frame.get_length());
-	int tail = FindTail(frame.get_buf(), frame.get_length());
-
-	if (tail >= 0)
-	{
-		if (tail < frame.get_length() - 1)		//���������
-		{
-			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
-		}
-		if (head >= 0 && head < tail)
-		{
-			////���
-			Binary_buf data(frame.get_buf() + head, tail - head + 1);
-			if (data.is_equal_front( "$SLSSTP"))
-				type = BUF_STOP;
-			else if (data.is_equal_front( "$SLSSTA"))
-				type = BUF_START;
-			else if (data.is_equal_front( "$SCLRDY"))
-				type = BUF_READY;
-			else if (data.is_equal_front( "$SHWERR"))
-				type = BUF_ERROR;
-			else if (data.is_equal_front( "$N"))
-				type = BUF_DATA;
-
-			if (type == BUF_DATA)
-			{
-				////��������
-				points.clear();
-				if (data.get_length() <= 29)
-					return type;
-
-				////����
-				unsigned char angle_1 = 0;
-				unsigned char angle_2 = 0;
-				memcpy(&angle_1, (data.get_buf())+26, 1);
-				memcpy(&angle_2, (data.get_buf())+27, 1);
-				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
-				float start_angle = 0.0;
-				float freq = 0.0;
-
-				std::vector<float> distance;
-				if (GetData(&data, distance, freq, start_angle))
-				{
-					float beta = (beta_a)*DEGREES;
-					float sin_beta = sin(beta);
-					float cos_beta = cos(beta);
-					for (int i = 0; i < distance.size(); ++i)
-					{
-						if (distance[i] < 0.001)
-							continue;
-
-						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
-						float sin_alpha = sin(alpha);
-						float cos_alpha = cos(alpha);
-
-						float x = distance[i] * sin_alpha;
-						float y = distance[i] * cos_alpha * sin_beta;
-						float z = distance[i] * cos_alpha * cos_beta;
-
-						points.push_back(CPoint3D(x, y, z));
-					}
-					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
-				}
-
-			}
-			else if (type == BUF_STOP)
-			{
-				m_laser_statu = LASER_READY;
-			}
-		}
-	}
-	else if (head >= 0)
-	{
-		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
-	}
-
-	return type;
-}
-
-bool CSick511FileLaser::receive_buf_to_queue(Binary_buf& data)
-{
-	if (m_start_read == false)
-		return false;
-	if (!m_stream_read.is_open())
-		return false;
-
-	if (m_stream_read.eof())
-	{
-		stop_scan();
-		m_stream_read.close();
-		usleep(100*1000);
-		m_stream_read.open(m_file.c_str(), ios::in | ios::binary);
-	}
-
-	char buf[512] = { 0 };
-	m_stream_read.read(buf, 512);
-	int count = m_stream_read.gcount();
-	if (count > 0)
-	{
-		Binary_buf bin_data(buf, count);
-		data = bin_data;
-		return true;
-	}
-	return false;
-}
-
-int CSick511FileLaser::FindHead(char* buf, int b_len)
-{
-	int i = 0;
-	if (b_len < 2)
-		return 0;
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len > 10)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
-				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
-				return i;
-		}
-		if (b_len > 7)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7] == '*')
-				return i;
-		}
-	}
-	return -1;
-}
-
-int CSick511FileLaser::FindTail(char* buf, int b_len)
-{
-	int i = 0;
-
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len >= i + 5)
-		{
-			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
-				return i + 4;
-		}
-	}
-	return -9999999;
-}
-
-bool CSick511FileLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
-								float& freq, float& start_angle)
-{
-	struct stData
-	{
-		const char* data;
-		int length;
-	};
-	std::vector<struct stData> strDatas;
-	int start = 0;
-	int end = 0;
-	int LMDscandata_index = -1;
-	for (int i = 0; i < pData->get_length(); ++i)
-	{
-		if ((*pData)[i] == ' ')
-		{
-			end = i;
-			if (end > start)
-			{
-				struct stData strData;
-//				strData.data = (*pData + start);
-				strData.data = ( pData->get_buf() + start);
-				strData.length = end - start;
-
-				strDatas.push_back(strData);
-				if (strncmp(strData.data, "LMDscandata", 11) == 0)
-					LMDscandata_index = strDatas.size() - 1;
-			}
-			end = i + 1;
-			start = end;
-		}
-	}
-
-	if (strDatas.size() > 26 + LMDscandata_index - 1)
-	{
-		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
-		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
-		start_angle = float(start_angle_l)*0.01;
-
-		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
-		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
-		freq = float(freq_l)*0.0001;
-
-		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
-		long count = Str0x2Long(count_str.data, count_str.length);
-		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
-		{
-			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
-			{
-				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
-				distance.push_back(dis);
-			}
-			return true;
-		}
-	}
-	return false;
-}
-long CSick511FileLaser::Str0x2Long(const char* data, int len)
-{
-	long sum = 0;
-	for (int i = 0; i < len; ++i)
-	{
-		char c = data[i];
-		int n = 0;
-		if (c >= 48 && c <= 57)
-			n = c - 48;
-		else if (c >= 65 && c <= 70)
-			n = c - 65 + 10;
-		sum += n*pow(16, len - i - 1);
-	}
-	return sum;
-}

+ 0 - 55
laser/Sick511FileLaser.h

@@ -1,55 +0,0 @@
-/*************************
-sick 511 �״� �ļ����ݽ���
-*************************/
-#ifndef __SICK_511_LASER_FILE__HH
-#define __SICK_511_LASER_FILE__HH
-#include "Laser.h"
-#include <fstream>
-class CSick511FileLaser :
-	public Laser_base
-{
-public:
-	CSick511FileLaser(int id, Laser_proto::laser_parameter laser_param);
-	virtual ~CSick511FileLaser();
-
-	//雷达链接设备,为3个线程添加线程执行函数。
-	virtual Error_manager connect_laser();
-	//雷达断开链接,释放3个线程
-	virtual Error_manager disconnect_laser();
-	//对外的接口函数,负责接受并处理任务单,
-	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-	virtual Error_manager execute_task(Task_Base* p_laser_task);
-	//检查雷达状态,是否正常运行
-	virtual Error_manager check_laser();
-	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-	virtual Error_manager start_scan();
-	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-	virtual Error_manager stop_scan();
-	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-	virtual Error_manager end_task();
-
-protected:
-	//接受二进制消息的功能函数,每次只接受一个CBinaryData
-	// 纯虚函数,必须由子类重载,
-	virtual bool receive_buf_to_queue(Binary_buf& data);
-	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
-	// 纯虚函数,必须由子类重载,
-	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
-
-
-protected:
-	int FindHead(char* buf, int b_len);
-	int FindTail(char* buf, int b_len);
-protected:
-	virtual bool GetData(Binary_buf* pData, std::vector<float>& distance,
-		float& freq, float& start_angle);
-	long Str0x2Long(const char* data, int len);
-
-protected:
-	std::ifstream	m_stream_read;
-	std::string		m_file;
-	bool			m_start_read;
-	std::mutex		m_mutex;
-};
-#endif

+ 0 - 343
laser/TcpLaser.cpp

@@ -1,343 +0,0 @@
-#include "TcpLaser.h"
-#include <stdlib.h>
-#include <unistd.h>
-
-RegisterLaser(Tcp);
-CTcpLaser::CTcpLaser(int id, Laser_proto::laser_parameter laser_param)
-	:Laser_base(id,laser_param)
-{
-}
-
-CTcpLaser::~CTcpLaser()
-{
-}
-
-
-
-
-//雷达链接设备,为3个线程添加线程执行函数。
-Error_manager CTcpLaser::connect_laser()
-{
-	std::string ip = m_laser_param.laser_ip();
-	int			port = m_laser_param.laser_port();
-	int			remoteport = m_laser_param.laser_port_remote();
-	if (ip == "" || port < 0)
-		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
-							" m_laser_param PARAMRTER ERROR ");
-
-	//��ʼ��Socket
-	//WSAStartup(MAKEWORD(1, 1), &m_wsd);
-	//����Socket����
-	m_socket = socket(AF_INET, SOCK_STREAM, 0);
-	if (m_socket <= 0)
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							 " m_laser_param PARAMRTER ERROR ");
-
-	m_send_addr.sin_family = AF_INET;
-	m_send_addr.sin_addr.s_addr = inet_addr(ip.c_str());
-	m_send_addr.sin_port = htons(remoteport);
-
-	if (0 != ::connect(m_socket, (struct sockaddr *)&m_send_addr, sizeof(struct sockaddr)))
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							 " connect m_socket ERROR ");
-	m_last_data_time = clock();
-	return Laser_base::connect_laser();
-}
-//雷达断开链接,释放3个线程
-Error_manager CTcpLaser::disconnect_laser()
-{
-	if (m_socket > 0)
-	{
-		close(m_socket);
-		//	WSACleanup();
-		m_socket = -1;
-	}
-	return Laser_base::disconnect_laser();
-}
-//对外的接口函数,负责接受并处理任务单,
-//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-Error_manager CTcpLaser::execute_task(Task_Base* p_laser_task)
-{
-
-}
-//检查雷达状态,是否正常运行
-Error_manager CTcpLaser::check_laser()
-{
-
-}
-//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-Error_manager CTcpLaser::start_scan()
-{
-	std::lock_guard<std::mutex> lk(m_mutex);
-	if (!this->is_ready())
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							"  is_ready ERROR ");
-
-	const char* sendMsg = "$SLSSTA*0A\r\n";
-	if (Send(sendMsg, strlen(sendMsg)))
-	{
-		return Laser_base::start_scan();
-	}
-	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-						" Send error ");
-}
-//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-Error_manager CTcpLaser::stop_scan()
-{
-	char sendMsg[] = "$SLSSTP*1B\r\n";
-	std::lock_guard<std::mutex> lk(m_mutex);
-	if (Send(sendMsg, strlen(sendMsg)))
-		return Error_code::SUCCESS;
-	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-						" error ");
-}
-//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-Error_manager CTcpLaser::end_task()
-{
-
-}
-
-
-Buf_type CTcpLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
-{
-	////ƴ���ϴ�δ�������
-
-	Buf_type type = BUF_UNKNOW;
-	Binary_buf frame;
-
-	if (m_last_data.get_length() > 0)
-	{
-		if (pData)
-			frame = m_last_data + (*pData);
-		else
-			frame = m_last_data;
-		m_last_data = Binary_buf();
-	}
-	else if (pData)
-	{
-		frame = (*pData);
-	}
-	else
-	{
-		return type;
-	}
-
-	int head = FindHead(frame.get_buf(), frame.get_length());
-	int tail = FindTail(frame.get_buf(), frame.get_length());
-
-	if (tail >= 0)
-	{
-		if (tail < frame.get_length() - 1)		//���������
-		{
-			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
-		}
-		if (head >= 0 && head < tail)
-		{
-			////���
-			Binary_buf data(frame.get_buf() + head, tail - head + 1);
-			if (data.is_equal_front("$SLSSTP") )
-				type = BUF_STOP;
-			else if (data.is_equal_front( "$SLSSTA"))
-				type = BUF_START;
-			else if (data.is_equal_front( "$SCLRDY"))
-				type = BUF_READY;
-			else if (data.is_equal_front( "$SHWERR"))
-				type = BUF_ERROR;
-			else if (data.is_equal_front( "$N"))
-				type = BUF_DATA;
-
-			if (type == BUF_DATA)
-			{
-				////��������
-				points.clear();
-				if (data.get_length() <= 29)
-					return type;
-
-				////����
-				unsigned char angle_1 = 0;
-				unsigned char angle_2 = 0;
-				memcpy(&angle_1, (data.get_buf())+26, 1);
-				memcpy(&angle_2, (data.get_buf())+27, 1);
-				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
-				float start_angle = 0.0;
-				float freq = 0.0;
-
-				std::vector<float> distance;
-				if (GetData(&data, distance, freq, start_angle))
-				{
-					float beta = (beta_a)*DEGREES;
-					float sin_beta = sin(beta);
-					float cos_beta = cos(beta);
-					for (int i = 0; i < distance.size(); ++i)
-					{
-						if (distance[i] < 0.001)
-							continue;
-
-						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
-						float sin_alpha = sin(alpha);
-						float cos_alpha = cos(alpha);
-
-						float x = distance[i] * sin_alpha;
-						float y = distance[i] * cos_alpha * sin_beta;
-						float z = distance[i] * cos_alpha * cos_beta;
-
-						points.push_back(CPoint3D(x, y, z));
-					}
-					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
-				}
-
-			}
-		}
-	}
-	else if (head >= 0)
-	{
-		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
-	}
-
-	return type;
-}
-
-bool CTcpLaser::receive_buf_to_queue(Binary_buf& data)
-{
-	char buf[4096] = { 0 };
-	int bytesRead = Recv(buf, 4096);
-	if (bytesRead > 0)
-	{
-		Binary_buf bin_data(buf, bytesRead);
-		data = bin_data;
-		m_last_data_time = clock();
-		return true;
-	}
-	return false;
-}
-
-int CTcpLaser::FindHead(char* buf, int b_len)
-{
-	int i = 0;
-	if (b_len < 2)
-		return 0;
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len > 10)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
-				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
-				return i;
-		}
-		if (b_len > 7)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7] == '*')
-				return i;
-		}
-	}
-	return -1;
-}
-
-int CTcpLaser::FindTail(char* buf, int b_len)
-{
-	int i = 0;
-
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len >= i + 5)
-		{
-			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
-				return i + 4;
-		}
-	}
-	return -9999999;
-}
-
-bool CTcpLaser::Send(const char* sendbuf, int len)
-{
-	int ret = 0;
-	do
-	{
-        ret = send(m_socket, sendbuf, strlen(sendbuf), 0);
-	} while (ret < 0);
-	return ret == len;
-}
-int CTcpLaser::Recv(char* recvbuf, int len)
-{
-	struct sockaddr_in sddr_from;
-	int ret = 0;
-	do
-	{
-        ret = recv(m_socket, recvbuf, 4096, 0);
-	} while (ret < 0);
-	return ret;
-}
-
-bool CTcpLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
-	float& freq, float& start_angle)
-{
-	struct stData
-	{
-		const char* data;
-		int length;
-	};
-	std::vector<struct stData> strDatas;
-	int start = 0;
-	int end = 0;
-	int LMDscandata_index = -1;
-	for (int i = 0; i < pData->get_length(); ++i)
-	{
-		if ((*pData)[i] == ' ')
-		{
-			end = i;
-			if (end > start)
-			{
-				struct stData strData;
-//				strData.data = (*pData + start);
-				strData.data = (pData->get_buf() + start);
-				strData.length = end - start;
-
-				strDatas.push_back(strData);
-				if (strncmp(strData.data, "LMDscandata", 11) == 0)
-					LMDscandata_index = strDatas.size() - 1;
-			}
-			end = i + 1;
-			start = end;
-		}
-	}
-
-	if (strDatas.size() > 26 + LMDscandata_index - 1)
-	{
-		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
-		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
-		start_angle = float(start_angle_l)*0.01;
-
-		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
-		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
-		freq = float(freq_l)*0.0001;
-
-		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
-		long count = Str0x2Long(count_str.data, count_str.length);
-		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
-		{
-			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
-			{
-				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
-				distance.push_back(dis);
-			}
-			return true;
-		}
-	}
-	return false;
-}
-long CTcpLaser::Str0x2Long(const char* data, int len)
-{
-	long sum = 0;
-	for (int i = 0; i < len; ++i)
-	{
-		char c = data[i];
-		int n = 0;
-		if (c >= 48 && c <= 57)
-			n = c - 48;
-		else if (c >= 65 && c <= 70)
-			n = c - 65 + 10;
-		sum += n*pow(16, len - i - 1);
-	}
-	return sum;
-}

+ 0 - 68
laser/TcpLaser.h

@@ -1,68 +0,0 @@
-/*************************
-sick 511 �״� tcpЭ�����ӿ��ư�
-*************************/
-
-#pragma once
-#include "Laser.h"
-#include <sys/types.h>
-#include <sys/socket.h>
-#include <netinet/in.h>
-#include <arpa/inet.h>
-#include <mutex>
-
-#define LASER_DATA_TIME_OUT		10000
-
-class CTcpLaser :
-	public Laser_base
-{
-public:
-	CTcpLaser(int id, Laser_proto::laser_parameter laser_param);
-	~CTcpLaser();
-
-	//雷达链接设备,为3个线程添加线程执行函数。
-	virtual Error_manager connect_laser();
-	//雷达断开链接,释放3个线程
-	virtual Error_manager disconnect_laser();
-	//对外的接口函数,负责接受并处理任务单,
-	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-	virtual Error_manager execute_task(Task_Base* p_laser_task);
-	//检查雷达状态,是否正常运行
-	virtual Error_manager check_laser();
-	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-	virtual Error_manager start_scan();
-	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-	virtual Error_manager stop_scan();
-	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-	virtual Error_manager end_task();
-
-protected:
-	//接受二进制消息的功能函数,每次只接受一个CBinaryData
-	// 纯虚函数,必须由子类重载,
-	virtual bool receive_buf_to_queue(Binary_buf& data);
-	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
-	// 纯虚函数,必须由子类重载,
-	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
-
-
-private:
-	bool	Send(const char* sendbuf, int len);                          // ����ָ��
-	int		Recv(char* recvbuf, int len);                           // ��������
-	static int FindHead(char* buf, int b_len);
-	static int FindTail(char* buf, int b_len);
-private:
-	bool GetData(Binary_buf* pData, std::vector<float>& distance,
-		float& freq, float& start_angle);
-	long Str0x2Long(const char* data, int len);
-
-private:
-#pragma region udp��ر���
-	int				m_socket;
-    //WSADATA			m_wsd;
-	struct sockaddr_in m_send_addr;	
-	std::mutex		m_mutex;
-	clock_t			m_last_data_time;
-#pragma endregion
-
-};
-

+ 0 - 352
laser/UdpLaser.cpp

@@ -1,352 +0,0 @@
-
-#include "UdpLaser.h"
-#include <stdlib.h>
-#include <unistd.h>
-
-RegisterLaser(Udp);
-CUdpLaser::CUdpLaser(int id, Laser_proto::laser_parameter laser_param)
-	:Laser_base(id,laser_param)
-{
-}
-
-
-CUdpLaser::~CUdpLaser()
-{
-}
-
-
-
-//雷达链接设备,为3个线程添加线程执行函数。
-Error_manager CUdpLaser::connect_laser()
-{
-	std::string ip = m_laser_param.laser_ip();
-	int			port = m_laser_param.laser_port();
-	int			remoteport = m_laser_param.laser_port_remote();
-	if (ip == "" || port < 0)
-		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
-							" m_laser_param PARAMRTER_ERROR ");
-
-	//��ʼ��Socket
-	//WSAStartup(MAKEWORD(1, 1), &m_wsd);
-	//����Socket����
-	m_socket = socket(AF_INET, SOCK_DGRAM, 0);
-	if (m_socket <= 0)
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							" m_socket PARAMRTER_ERROR ");
-
-	struct sockaddr_in sddr_udp;
-	sddr_udp.sin_family = AF_INET;
-	sddr_udp.sin_addr.s_addr = htons(INADDR_ANY);
-	sddr_udp.sin_port = htons(port);
-
-	m_send_addr.sin_family = AF_INET;
-	m_send_addr.sin_addr.s_addr = inet_addr(ip.c_str());
-	m_send_addr.sin_port = htons(remoteport);
-
-	if(-1==bind(m_socket, (struct sockaddr *)&sddr_udp, sizeof(struct sockaddr)))
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							" bind m_socket  ERROR ");
-
-	return Laser_base::connect_laser();
-}
-//雷达断开链接,释放3个线程
-Error_manager CUdpLaser::disconnect_laser()
-{
-	if (m_socket > 0)
-	{
-
-		close(m_socket);
-		//WSACleanup();
-		m_socket = -1;
-	}
-	return Laser_base::disconnect_laser();
-}
-//对外的接口函数,负责接受并处理任务单,
-//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-Error_manager CUdpLaser::execute_task(Task_Base* p_laser_task)
-{
-
-}
-//检查雷达状态,是否正常运行
-Error_manager CUdpLaser::check_laser()
-{
-
-}
-//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-Error_manager CUdpLaser::start_scan()
-{
-	std::lock_guard<std::mutex> lk(m_mutex);
-	if (!this->is_ready())
-		return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-							"is_ready error ");
-
-	const char* sendMsg = (char*)"$SLSSTA*0A\r\n";
-	if (Send(sendMsg, strlen(sendMsg)))
-	{
-		m_laser_statu = LASER_BUSY;
-
-		return Laser_base::start_scan();
-	}
-	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-						" Send error ");
-}
-//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-Error_manager CUdpLaser::stop_scan()
-{
-	const char sendMsg[] = "$SLSSTP*1B\r\n";
-	std::lock_guard<std::mutex> lk(m_mutex);
-	if (Send(sendMsg, strlen(sendMsg)))
-		return Error_code::SUCCESS;
-	return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-						" Send error ");
-}
-//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-Error_manager CUdpLaser::end_task()
-{
-
-}
-
-
-Buf_type CUdpLaser::transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points)
-{
-	////ƴ���ϴ�δ�������
-
-	Buf_type type = BUF_UNKNOW;
-	Binary_buf frame;
-
-	if (m_last_data.get_length() > 0)
-	{
-		if (pData)
-			frame = m_last_data + (*pData);
-		else
-			frame = m_last_data;
-		m_last_data = Binary_buf();
-	}
-	else if (pData)
-	{
-		frame = (*pData);
-	}
-	else
-	{
-		return type;
-	}
-
-	int head = FindHead(frame.get_buf(), frame.get_length());
-	int tail = FindTail(frame.get_buf(), frame.get_length());
-	if (tail >= 0)
-	{
-		if (tail < frame.get_length() - 1)		//���������
-		{
-			m_last_data = Binary_buf(frame.get_buf() + tail + 1, frame.get_length() - tail - 1);
-		}
-		if (head >= 0 && head < tail)
-		{
-			////���
-			Binary_buf data(frame.get_buf() + head, tail - head + 1);
-			if (data.is_equal_front( "$SLSSTP"))
-				type = BUF_STOP;
-			else if (data.is_equal_front( "$SLSSTA"))
-				type = BUF_START;
-			else if (data.is_equal_front( "$SCLRDY"))
-				type = BUF_READY;
-			else if (data.is_equal_front( "$SHWERR"))
-				type = BUF_ERROR;
-			else if (data.is_equal_front( "$N"))
-				type = BUF_DATA;
-
-			if (type == BUF_DATA)
-			{
-				////��������
-				points.clear();
-				if (data.get_length() <= 29)
-					return type;
-
-				////����
-				unsigned char angle_1 = 0;
-				unsigned char angle_2 = 0;
-				memcpy(&angle_1, (data.get_buf())+26, 1);
-				memcpy(&angle_2, (data.get_buf())+27, 1);
-				float beta_a = float(angle_1 * 256 + angle_2)*0.01;
-				float start_angle = 0.0;
-				float freq = 0.0;
-
-				std::vector<float> distance;
-				if (GetData(&data, distance, freq, start_angle))
-				{
-					
-					float beta = (beta_a)*DEGREES;
-					float sin_beta = sin(beta);
-					float cos_beta = cos(beta);
-					for (int i = 0; i < distance.size(); ++i)
-					{
-						if (distance[i] < 0.001)
-							continue;
-
-						float alpha = (start_angle + i*freq - 90.0) * DEGREES;
-						float sin_alpha = sin(alpha);
-						float cos_alpha = cos(alpha);
-
-						float x = distance[i] * sin_alpha;
-						float y = distance[i] * cos_alpha * sin_beta;
-						float z = distance[i] * cos_alpha * cos_beta;
-
-						points.push_back(CPoint3D(x, y, z));
-					}
-					//points.push_back(CPoint3D(double(distance.size()), start_angle, freq));
-				}
-
-			}
-		}
-	}
-	else if (head >= 0)
-	{
-		m_last_data = Binary_buf(frame.get_buf() + head, frame.get_length() - head);
-	}
-	
-	return type;
-}
-
-bool CUdpLaser::receive_buf_to_queue(Binary_buf& data)
-{
-	char buf[4096 * 10] = { 0 };
-    int bytesRead = Recv(buf, 4096);
-	if (bytesRead > 0)
-	{
-		Binary_buf bin_data(buf, bytesRead);
-		data = bin_data;
-		return true;
-	}
-	return false;
-}
-
-int CUdpLaser::FindHead(char* buf, int b_len)
-{
-	int i = 0;
-	if (b_len < 2)
-		return 0;
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len > 10)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'N' && buf[i + 7] == 'S'
-				&&buf[i + 8] == '5'&&buf[i + 9] == '1'&&buf[i + 10] == '1')
-				return i;
-		}
-		if (b_len >7)
-		{
-			if (buf[i] == '$'&& buf[i + 1] == 'S'&&buf[i + 7]=='*')
-				return i;
-		}
-	}
-	return -1;
-}
-
-int CUdpLaser::FindTail(char* buf, int b_len)
-{
-	int i = 0;
-	
-	for (i = 0; i <= b_len; i++)
-	{
-		if (b_len >=i+ 5)
-		{
-			if (buf[i] == '*' && buf[i + 3] == '\r'&&buf[i + 4] == '\n')
-				return i+4;
-		}
-	}
-	return -9999999;
-}
-
-bool CUdpLaser::Send(const char* sendbuf, int len)
-{
-	int ret = 0;
-	do 
-	{
-        ret = sendto(m_socket, sendbuf, strlen(sendbuf), 0, (struct sockaddr*)&m_send_addr, sizeof(struct sockaddr));
-	} while (ret < 0);
-	return ret == len;
-}
-int CUdpLaser::Recv(char* recvbuf, int len)
-{
-	struct sockaddr_in sddr_from;
-    socklen_t clientLen = sizeof(sddr_from);
-	int ret = 0;
-	do
-	{
-        ret = recvfrom(m_socket, recvbuf, 4096, 0, (struct sockaddr*)&sddr_from, &clientLen);
-	} while (ret < 0);
-	return ret;
-}
-
-bool CUdpLaser::GetData(Binary_buf* pData, std::vector<float>& distance,
-	float& freq, float& start_angle)
-{
-	struct stData
-	{
-		const char* data;
-		int length;
-	};
-	std::vector<struct stData> strDatas;
-	int start = 0;
-	int end = 0;
-	int LMDscandata_index = -1;
-	for (int i = 0; i < pData->get_length(); ++i)
-	{
-		if ((*pData)[i] == ' ')
-		{
-			end = i;
-			if (end > start)
-			{
-				struct stData strData;
-//				strData.data = (*pData + start);
-				strData.data = (pData->get_buf() + start);
-				strData.length = end - start;
-				
-				strDatas.push_back(strData);
-				if (strncmp(strData.data, "LMDscandata", 11) == 0)
-					LMDscandata_index = strDatas.size() - 1;
-			}
-			end = i + 1;
-			start = end;
-		}
-	}
-
-	if (strDatas.size() > 26 + LMDscandata_index - 1)
-	{
-		struct stData start_angle_str = strDatas[23 + LMDscandata_index - 1];
-		long start_angle_l = Str0x2Long(start_angle_str.data, start_angle_str.length);
-		start_angle = float(start_angle_l)*0.01;
-
-		struct stData freq_str = strDatas[24 + LMDscandata_index - 1];
-		long freq_l = Str0x2Long(freq_str.data, freq_str.length);
-		freq = float(freq_l)*0.0001;
-
-		struct stData count_str = strDatas[25 + LMDscandata_index - 1];
-		long count = Str0x2Long(count_str.data, count_str.length);
-		if (strDatas.size() >= 26 + LMDscandata_index - 1 + count)
-		{
-			for (int i = 26 + LMDscandata_index - 1; i < 26 + LMDscandata_index - 1 + count; ++i)
-			{
-				float dis = float(Str0x2Long(strDatas[i].data, strDatas[i].length));
-				distance.push_back(dis);
-			}
-			return true;
-		}
-	}
-	return false;
-}
-long CUdpLaser::Str0x2Long(const char* data, int len)
-{
-	long sum = 0;
-	for (int i = 0; i < len; ++i)
-	{
-		char c = data[i];
-		int n = 0;
-		if (c >= 48 && c <= 57)
-			n = c - 48;
-		else if (c >= 65 && c <= 70)
-			n = c - 65 + 10;
-		sum += n*pow(16, len - i - 1);
-	}
-	return sum;
-}

+ 0 - 61
laser/UdpLaser.h

@@ -1,61 +0,0 @@
-/*************************
-sick 511 �״� updЭ�����ӿ��ư�
-*************************/
-#pragma once
-#include "Laser.h"
-#include <sys/types.h>
-#include <sys/socket.h>
-#include <netinet/in.h>
-#include <arpa/inet.h>
-#include <mutex>
-class CUdpLaser : public Laser_base
-{
-public:
-	CUdpLaser(int id, Laser_proto::laser_parameter laser_param);
-	virtual ~CUdpLaser();
-
-	//雷达链接设备,为3个线程添加线程执行函数。
-	virtual Error_manager connect_laser();
-	//雷达断开链接,释放3个线程
-	virtual Error_manager disconnect_laser();
-	//对外的接口函数,负责接受并处理任务单,
-	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-	//注:这个函数为虚函数,实际的处理任务的代码由子类重载并实现。
-	virtual Error_manager execute_task(Task_Base* p_laser_task);
-	//检查雷达状态,是否正常运行
-	virtual Error_manager check_laser();
-	//雷达的启动接口函数, 让雷达进行扫描,一般需要子类重载,不同的雷达开始方式不同。
-	virtual Error_manager start_scan();
-	//雷达的停止接口函数, 让雷达停止扫描,一般需要子类重载,不同的雷达结束方式不同。
-	virtual Error_manager stop_scan();
-	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-	virtual Error_manager end_task();
-
-protected:
-	//接受二进制消息的功能函数,每次只接受一个CBinaryData
-	// 纯虚函数,必须由子类重载,
-	virtual bool receive_buf_to_queue(Binary_buf& data);
-	//将二进制消息转化为三维点云的功能函数,每次只转化一个CBinaryData,
-	// 纯虚函数,必须由子类重载,
-	virtual Buf_type transform_buf_to_points(Binary_buf* pData, std::vector<CPoint3D>& points);
-	
-
-private:
-	bool Send(const char* sendbuf, int len);                          // ����ָ��
-	int Recv(char* recvbuf, int len);                           // ��������
-	static int FindHead(char* buf, int b_len);
-	static int FindTail(char* buf, int b_len);
-private:
-	bool GetData(Binary_buf* pData, std::vector<float>& distance,
-		float& freq, float& start_angle);
-	long Str0x2Long(const char* data, int len);
-
-protected:
-#pragma region udp��ر���
-	int				m_socket;
-//	WSADATA			m_wsd;
-	struct sockaddr_in m_send_addr;
-	std::mutex		m_mutex;
-#pragma endregion
-};
-

+ 0 - 406
laser/laser_manager.cpp

@@ -1,406 +0,0 @@
-
-
-
-#include "./laser_manager.h"
-
-#include "../tool/proto_tool.h"
-#include "../laser/laser_parameter.pb.h"
-
-#include <livox_sdk.h>
-
-Laser_manager::Laser_manager()
-{
-	m_laser_manager_status = LASER_MANAGER_UNKNOW;
-	mp_laser_manager_thread = NULL;
-
-	mp_laser_manager_task = NULL;
-	m_laser_number = 0;
-}
-Laser_manager::~Laser_manager()
-{
-	laser_manager_uninit();
-}
-
-//初始化 雷达 管理模块。如下三选一
-Error_manager Laser_manager::laser_manager_init()
-{
-	return  laser_manager_init_from_protobuf(LASER_PARAMETER_ALL_PATH);
-}
-//初始化 雷达 管理模块。从文件读取
-Error_manager Laser_manager::laser_manager_init_from_protobuf(std::string prototxt_path)
-{
-	Laser_proto::Laser_parameter_all laser_parameters;
-
-	if(!  proto_tool::read_proto_param(prototxt_path,laser_parameters) )
-	{
-		return Error_manager(LASER_MANAGER_READ_PROTOBUF_ERROR,MINOR_ERROR,"Laser_manager read_proto_param  failed");
-	}
-
-	return laser_manager_init_from_protobuf(laser_parameters);
-}
-//初始化 雷达 管理模块。从protobuf读取
-Error_manager Laser_manager::laser_manager_init_from_protobuf(Laser_proto::Laser_parameter_all& laser_parameters)
-{
-	m_laser_manager_status = LASER_MANAGER_READY;
-	m_laser_number = laser_parameters.laser_parameters_size();
-	m_laser_manager_working_flag = false;
-
-	//创建大疆雷达
-	int laser_cout=laser_parameters.laser_parameters_size();
-	m_laser_vector.resize(laser_cout);
-	for(int i=0;i<laser_parameters.laser_parameters_size();++i)
-	{
-		m_laser_vector[i]=LaserRegistory::CreateLaser(laser_parameters.laser_parameters(i).type(),i,
-													  laser_parameters.laser_parameters(i));
-		if(m_laser_vector[i]!=NULL)
-		{
-			if(m_laser_vector[i]->connect_laser()!=SUCCESS)
-			{
-				char description[255]={0};
-				sprintf(description,"Laser %d connect failed...",i);
-				return Error_manager(LASER_CONNECT_FAILED,NORMAL,description);
-			}
-		}
-	}
-	//查询是否有livox雷达,初始化库
-	for (int i = 0; i < laser_parameters.laser_parameters_size(); ++i)
-	{
-		std::string type = laser_parameters.laser_parameters(i).type();
-		if (type.find("Livox") != type.npos)
-		{
-			if (Start() == false)
-			{
-				Uninit();
-				return Error_manager(LASER_LIVOX_SKD_INIT_FAILED,NORMAL,"Livox laser init failed...");
-			}
-			break;
-		}
-	}
-
-	//启动雷达管理模块的内部线程。默认wait。
-	m_laser_manager_condition.reset(false, false, false);
-	mp_laser_manager_thread = new std::thread(&Laser_manager::thread_work, this);
-
-	return Error_code::SUCCESS;
-}
-//反初始化 雷达 管理模块。
-Error_manager Laser_manager::laser_manager_uninit()
-{
-
-	//关闭线程
-	if (mp_laser_manager_thread)
-	{
-		m_laser_manager_condition.kill_all();
-	}
-	//回收线程的资源
-	if (mp_laser_manager_thread)
-	{
-		mp_laser_manager_thread->join();
-		delete mp_laser_manager_thread;
-		mp_laser_manager_thread = NULL;
-	}
-
-	//回收雷达的内存
-	for (int i = 0; i < m_laser_number; ++i)
-	{
-		delete(m_laser_vector[i]);
-	}
-	//回收下发雷达任务单
-	for (map<int, Laser_task*>::iterator iter  = m_laser_task_map.begin(); iter != m_laser_task_map.end(); ++iter)
-	{
-		delete(iter->second);
-		m_laser_task_map.erase(iter);
-	}
-}
-
-
-
-//对外的接口函数,负责接受并处理任务单,
-//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-Error_manager Laser_manager::execute_task(Task_Base* p_laser_task)
-{
-	LOG(INFO) << " Laser_manager::execute_task start  "<< this;
-	Error_manager t_error;
-	Error_manager t_result;
-
-	//检查指针
-	if (p_laser_task == NULL) {
-		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
-							 "Laser_manager::execute_task failed, POINTER_IS_NULL");
-	}
-	//检查任务类型,
-	if (p_laser_task->get_task_type() != LASER_MANGER_SCAN_TASK)
-	{
-		return Error_manager(Error_code::LIVOX_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
-							 "laser task type error != LASER_MANGER_SCAN_TASK ");
-	}
-
-	//接受任务,并将任务的状态改为TASK_SIGNED已签收
-	mp_laser_manager_task = (Laser_manager_task *) p_laser_task;
-	mp_laser_manager_task->set_task_statu(TASK_SIGNED);
-
-	//检查消息内容是否正确,
-	//检查三维点云指针
-	if (mp_laser_manager_task->get_task_point_cloud().get() == NULL)
-	{
-		t_result.error_manager_reset(Error_code::POINTER_IS_NULL,
-									 Error_level::MINOR_ERROR,
-									 "execute_task mp_task_point_cloud is null");
-		//将任务的状态改为 TASK_ERROR 结束错误
-		mp_laser_manager_task->set_task_statu(TASK_ERROR);
-		//返回错误码
-		mp_laser_manager_task->set_task_error_manager(t_result);
-		return t_result;
-	}
-	else
-	{
-		if ( m_laser_manager_status != LASER_MANAGER_READY )
-		{
-			t_result.error_manager_reset(Error_code::LASER_MANAGER_IS_NOT_READY,
-										 Error_level::MINOR_ERROR,
-										 "execute_task m_laser_manager_status != LASER_MANAGER_READY");
-			//将任务的状态改为 TASK_ERROR 结束错误
-			mp_laser_manager_task->set_task_statu(TASK_ERROR);
-			//返回错误码
-			mp_laser_manager_task->set_task_error_manager(t_result);
-			return t_result;
-		}
-		else
-		{
-			//启动雷达管理模块,的核心工作线程
-			m_laser_manager_status = LASER_MANAGER_ISSUED_TASK;
-			m_laser_manager_working_flag = true;
-			m_laser_manager_condition.notify_all(true);
-			//通知 thread_work 子线程启动。
-
-			//将任务的状态改为 TASK_WORKING 处理中
-			mp_laser_manager_task->set_task_statu(TASK_WORKING);
-
-		}
-
-	}
-	//返回错误码
-	if (t_result != Error_code::SUCCESS)
-	{
-		//将任务的状态改为 TASK_ERROR 结束错误
-		mp_laser_manager_task->set_task_statu(TASK_ERROR);
-		//返回错误码
-		mp_laser_manager_task->set_task_error_manager(t_result);
-		return t_result;
-	}
-	return t_result;
-
-}
-
-//检查雷达状态,是否正常运行
-Error_manager Laser_manager::check_status()
-{
-
-}
-//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-Error_manager Laser_manager::end_task()
-{
-	LOG(INFO) << " Laser_manager::end_task "<< this;
-
-	m_laser_manager_working_flag=false;
-	m_laser_manager_condition.notify_all(false);
-
-	laser_task_map_clear_and_delete();
-
-	//在结束任务单时,将雷达任务状态改为 TASK_OVER 已结束
-	if(mp_laser_manager_task !=NULL)
-	{
-		//判断任务单的错误等级,
-		if ( mp_laser_manager_task->get_task_error_manager().get_error_level() < Error_level::MINOR_ERROR)
-		{
-			if ( m_laser_manager_status == LASER_MANAGER_ISSUED_TASK  || m_laser_manager_status == LASER_MANAGER_WAIT_REPLY)
-			{
-				//故障等级为 NORMAL NEGLIGIBLE_ERROR MINOR_ERROR,则恢复待机,可以接受下一次的任务单
-				m_laser_manager_status = LASER_MANAGER_READY;
-			}
-
-		}
-		else
-		{
-			//故障等级为 MAJOR_ERROR CRITICAL_ERROR,则雷达故障,不可以再接受任务单。
-			m_laser_manager_status = LASER_MANAGER_FAULT;
-		}
-		//强制改为TASK_OVER,不管它当前在做什么。
-		mp_laser_manager_task->set_task_statu(TASK_OVER);
-	}
-	std::cout << "------Laser_manager::end_task()------."<<mp_laser_manager_task->get_task_error_manager().to_string() << std::endl;
-	return Error_code::SUCCESS;
-}
-
-//释放下发的任务单
-Error_manager Laser_manager::laser_task_map_clear_and_delete()
-{
-	for ( map<int, Laser_task*>::iterator map_iter2 = m_laser_task_map.begin(); map_iter2 != m_laser_task_map.end(); )
-	{
-		//销毁下发的任务单。
-		delete(map_iter2->second);
-		map_iter2 = m_laser_task_map.erase(map_iter2);
-		//注:erase 删除当前map_iter2之后返回下一个节点,当前的map_iter2无效化,
-		//for循环不用 ++map_iter2
-	}
-	return Error_code::SUCCESS;
-}
-
-//下发给子雷达任务。这里为下发雷达任务分配内存, 后续要记得回收 m_laser_task_map 。
-Error_manager Laser_manager::issued_task(int laser_index)
-{
-	Error_manager t_error;
-
-	if ( laser_index < 0 || laser_index >= m_laser_number )
-	{
-	    return Error_manager(Error_code::LASER_MANAGER_LASER_INDEX_ERRPR, Error_level::MINOR_ERROR,
-	    					" issued_task laser_index  error ");
-	}
-
-	//创建雷达扫描任务,
-	// 这里为下发雷达任务分配内存,后续要记得回收。
-	Laser_task* t_laser_task=new Laser_task();
-	mp_laser_manager_task->trans_to_laser_task(t_laser_task,laser_index,m_laser_vector[laser_index],
-	TASK_CREATED,std::chrono::milliseconds(7000));
-
-	//保存雷达扫描任务 到 m_laser_task_map
-	map<int, Laser_task*>::iterator map_iter = m_laser_task_map.find(laser_index);
-	if ( map_iter != m_laser_task_map.end() )
-	{
-		//如果重复,则清除原有的,用新的覆盖。
-		delete(map_iter->second);
-		m_laser_task_map[laser_index] = t_laser_task;
-	}
-	else
-	{
-		m_laser_task_map[laser_index] = t_laser_task;
-	}
-
-	//发送任务单给雷达
-//	t_error=m_laser_vector[laser_index]->execute_task(t_laser_task);
-	task_command_manager::get_instance_references().execute_task(t_laser_task);
-
-	if(t_error!=SUCCESS)
-	{
-		;
-		//这里的故障处理很复杂,以后再写。
-		//部分成功,部分失败。
-	}
-
-	return t_error;
-
-}
-
-//mp_laser_manager_thread 线程执行函数,
-//thread_work 内部线程负责分发扫描任务给下面的雷达,并且回收汇总雷达的数据
-void Laser_manager::thread_work()
-{
-	LOG(INFO) << " mp_laser_manager_thread start "<< this;
-	Error_manager t_error;
-	Error_manager t_result;
-
-	//雷达管理的独立线程,负责控制管理所有的雷达。
-	while (m_laser_manager_condition.is_alive())
-	{
-		m_laser_manager_condition.wait();
-		if ( m_laser_manager_condition.is_alive() )
-		{
-			if ( mp_laser_manager_task == NULL )
-			{
-				m_laser_manager_status = LASER_MANAGER_FAULT;
-				m_laser_manager_working_flag = false;
-				m_laser_manager_condition.notify_all(false);
-			}
-			//下发任务
-			else if(m_laser_manager_status == LASER_MANAGER_ISSUED_TASK)
-			{
-				//分发扫描任务给下面的雷达
-				if ( mp_laser_manager_task->get_select_all_laser_flag() )
-				{
-					//下发任务给所有的雷达
-					for (int i = 0; i < m_laser_number; ++i)
-					{
-						//下发给子雷达任务。这里为下发雷达任务分配内存, 后续要记得回收 m_laser_task_map 。
-						t_error = issued_task(i);
-						if ( t_error != SUCCESS)
-						{
-							t_result.compare_and_cover_error(t_error);
-						}
-					}
-				}
-				else
-				{
-					//下发任务给选中的雷达
-					std::vector<int> & t_select_laser_id_vector = mp_laser_manager_task->get_select_laser_id_vector();
-					for (int i = 0; i < t_select_laser_id_vector.size(); ++i)
-					{
-						//下发给子雷达任务。这里为下发雷达任务分配内存, 后续要记得回收 m_laser_task_map 。
-						t_error = issued_task(t_select_laser_id_vector[i]);
-						if ( t_error != SUCCESS)
-						{
-							t_result.compare_and_cover_error(t_error);
-						}
-					}
-				}
-
-				//下发任务之后,修改状态为等待答复。
-				m_laser_manager_status = LASER_MANAGER_WAIT_REPLY;
-			}
-			//等待答复
-			else if(m_laser_manager_status == LASER_MANAGER_WAIT_REPLY)
-			{
-				map<int, Laser_task*>::iterator map_iter;
-				for (  map_iter = m_laser_task_map.begin(); map_iter != m_laser_task_map.end(); ++map_iter)
-				{
-					if ( map_iter->second->is_over_time() )
-					{
-						//超时处理。取消任务。
-						m_laser_vector[map_iter->first]->cancel_task();
-						map_iter->second->set_task_statu(TASK_DEAD);
-						t_error.error_manager_reset(Error_code::LASER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
-											" LASER_TASK is_over_time ");
-						map_iter->second->set_task_error_manager(t_error);
-					}
-					if (!( map_iter->second->get_task_statu() == TASK_OVER
-						 || map_iter->second->get_task_statu() == TASK_ERROR
-						 || map_iter->second->get_task_statu() == TASK_DEAD) )
-					{
-						//等待任务继续完成,等1ms
-						std::this_thread::sleep_for(std::chrono::milliseconds(1));
-						break;
-					}
-				}
-
-				//如果下发的任务全部结束,那么汇总所有的结果, 并销毁下发的任务单。
-				if(map_iter == m_laser_task_map.end() )
-				{
-					for ( map<int, Laser_task*>::iterator map_iter2 = m_laser_task_map.begin(); map_iter2 != m_laser_task_map.end(); )
-					{
-						//数据汇总,
-						//由于 pcl::PointCloud<pcl::PointXYZ>::Ptr mp_task_point_cloud; 是所有任务单共用的,所以不用处理了。自动就在一起。
-
-						//错误汇总
-						t_result.compare_and_cover_error(map_iter2->second->get_task_error_manager());
-
-						//销毁下发的任务单。
-						delete(map_iter2->second);
-						map_iter2 = m_laser_task_map.erase(map_iter2);
-						//注:erase 删除当前map_iter2之后返回下一个节点,当前的map_iter2无效化,
-						//for循环不用 ++map_iter2
-					}
-
-					mp_laser_manager_task->set_task_error_manager(t_result);
-					//结束任务
-					end_task();
-				}
-			}
-
-
-		}
-	}
-	LOG(INFO) << " mp_laser_manager_thread end :"<<this;
-	return;
-}
-
-
-

+ 0 - 116
laser/laser_manager.h

@@ -1,116 +0,0 @@
-
-/*
- * Laser_manager 是雷达模块的总管理类。
- * Laser_manager 作为一个单例,全局可以使用。 get_instance 系列的函数可获取唯一的实例。
- * 它作为一个独立的模块,不和外部有直接的联系。
- * 对外只有一个接口函数 execute_task 用以执行 任务单 Laser_manager_task
- *
- * Laser_manager模块内部包含了所有的雷达指针。
- * 还自带一个线程,用来控制雷达。
- *
- *
- * */
-
-
-
-#ifndef LASER_MANAGER_H
-#define LASER_MANAGER_H
-
-#include "../error_code/error_code.h"
-#include "../tool/singleton.h"
-#include "../tool/thread_condition.h"
-
-#include "../laser/Laser.h"
-#include "../laser/laser_manager_task.h"
-
-
-#define LASER_PARAMETER_ALL_PATH "../setting/laser.prototxt"
-
-class Laser_manager:public Singleton<Laser_manager>
-{
-	// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-	friend class Singleton<Laser_manager>;
-
-public:
-	//雷达管理模块的工作状态
-	enum Laser_manager_status
-	{//default LASER_MANAGER_UNKNOW = 0
-	    LASER_MANAGER_UNKNOW               	= 0,    //未知
-	    LASER_MANAGER_READY               	= 1,    //准备,待机
-		LASER_MANAGER_ISSUED_TASK			= 2,	//工作下发任务
-		LASER_MANAGER_WAIT_REPLY			= 3,	//工作等待答复
-		LASER_MANAGER_FAULT					= 4,	//故障
-	};
-public:
-	// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
-	Laser_manager(const Laser_manager&)=delete;
-	Laser_manager& operator =(const Laser_manager&)= delete;
-	~Laser_manager();
-private:
-	// 父类的构造函数必须保护,子类的构造函数必须私有。
-	Laser_manager();
-
-
-public: //API 对外接口
-	//初始化 雷达 管理模块。如下三选一
-	Error_manager laser_manager_init();
-	//初始化 雷达 管理模块。从文件读取
-	Error_manager laser_manager_init_from_protobuf(std::string prototxt_path);
-	//初始化 雷达 管理模块。从protobuf读取
-	Error_manager laser_manager_init_from_protobuf(Laser_proto::Laser_parameter_all& laser_parameters);
-	//反初始化 雷达 管理模块。
-	Error_manager laser_manager_uninit();
-
-
-	//对外的接口函数,负责接受并处理任务单,
-	//input:p_laser_task 雷达任务单,基类的指针,指向子类的实例,(多态)
-	Error_manager execute_task(Task_Base* p_laser_task);
-	//检查雷达状态,是否正常运行
-	Error_manager check_status();
-	//结束任务单,stop之后,要检查线程状态和数据结果,然后才能 end_task
-	Error_manager end_task();
-
-	//释放下发的任务单
-	Error_manager laser_task_map_clear_and_delete();
-
-public://get or set member variable
-
-
-protected:
-	//下发给子雷达任务。这里为下发雷达任务分配内存, 后续要记得回收 m_laser_task_map 。
-	Error_manager issued_task(int laser_index);
-
-	//mp_laser_manager_thread 线程执行函数,
-	//thread_work 内部线程负责分发扫描任务给下面的雷达,并且回收汇总雷达的数据
-	void thread_work();
-
-
-
-
-
-protected://member variable
-
-	Laser_manager_status						m_laser_manager_status;		//雷达管理模块的工作状态
-	int 										m_laser_number;					//雷达的个数
-	std::vector<Laser_base*>                    m_laser_vector;				//雷达的对象实例,内存由本类管理
-	//注意:里面的Laser_base*是在init里面new出来的,析构之前必须使用ununit来销毁
-
-	std::atomic<bool>                			m_laser_manager_working_flag;          //雷达管理的工作使能标志位
-	map<int, Laser_task*>						m_laser_task_map;					//雷达管理下发给雷达子模块的任务map,内存由本类管理
-
-
-	std::thread*        						mp_laser_manager_thread;   		//发布信息的线程指针,内存由本类管理
-	Thread_condition							m_laser_manager_condition;		//发布信息的条件变量
-
-
-	//雷达管理的任务单指针,实际内存由发送方控制管理,//接受任务后,指向新的任务单
-	Laser_manager_task *  						mp_laser_manager_task;        		//雷达管理任务单的指针,内存由发送方管理。
-
-private:
-
-};
-
-
-
-
-#endif //LASER_MANAGER_H

+ 0 - 256
laser/laser_manager_task.cpp

@@ -1,256 +0,0 @@
-
-/*
- * Laser_manager_task 是雷达管理的任务单。
- * 外部通过它对 Laser_manager 下发任务。
- *
-//用法:上级直接调用 Laser_manager 的接口函数 execute_task ,并将 Laser_manager_task 类作为参数传递
-// Laser_manager 类则按照 Laser_manager_task 的功能码和指定的参数,执行相应的功能
-//并将结果填充到 Laser_manager_task ,返回给上级。
- *
- *
- * */
-
-#include "laser_manager_task.h"
-
-
-//构造函数,构造函数锁定任务类型为 LASER_MANGER_SCAN_TASK ,后续不允许更改
-Laser_manager_task::Laser_manager_task()
-{
-//构造函数锁定任务类型为 LASER_MANGER_SCAN_TASK,后续不允许更改
-	m_task_type = LASER_MANGER_SCAN_TASK;
-	m_task_statu = TASK_CREATED;
-	m_task_statu_information.clear();
-	m_task_error_manager.error_manager_clear_all();
-
-	m_task_frame_maxnum = 0;
-	m_task_save_flag = false;//默认不保存,false
-	m_task_save_path.clear();
-	mp_task_point_cloud = NULL;
-	mp_task_cloud_lock=NULL;
-
-	m_select_all_laser_flag = true;
-	m_select_laser_id_vector.clear();
-}
-
-//析构函数
-Laser_manager_task::~Laser_manager_task()
-{
-
-}
-
-//初始化任务单,必须初始化之后才可以使用,(必选参数)
-// input:p_task_cloud_lock 三维点云的数据保护锁
-// output:p_task_point_cloud 三维点云容器的智能指针
-//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-Error_manager Laser_manager_task::task_init(std::mutex* p_task_cloud_lock,
-											pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud)
-{
-	if(p_task_point_cloud.get() == NULL)
-	{
-		return Error_manager(POINTER_IS_NULL, MINOR_ERROR,
-							 "Laser_task::task_init p_task_point_cloud is null");
-	}
-	if(p_task_cloud_lock==NULL)
-	{
-		return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
-							 "Laser_manager_task::task_init p_task_cloud_lock is null");
-	}
-
-	m_task_statu = TASK_CREATED;
-	m_task_statu_information.clear();
-	m_task_error_manager.error_manager_clear_all();
-
-	m_task_frame_maxnum = 0;
-	m_task_save_flag = false;
-	m_task_save_path.clear();
-	mp_task_cloud_lock=p_task_cloud_lock;
-	mp_task_point_cloud = p_task_point_cloud;
-
-	m_select_all_laser_flag = true;
-	m_select_laser_id_vector.clear();
-
-	return Error_code::SUCCESS;
-}
-
-//初始化任务单,必须初始化之后才可以使用,(可选参数)
-//    input:task_statu 任务状态
-//    input:task_statu_information 状态说明
-//    input:tast_receiver 接受对象
-//    input:task_over_time 超时时间
-//    input:task_frame_maxnum 点云的采集帧数最大值
-//    input:task_save_flag 是否保存
-//    input:task_save_path 保存路径
-//    input:p_task_cloud_lock 三维点云的数据保护锁
-//    output:p_task_point_cloud 三维点云容器的智能指针
-//    input:m_is_select_all_laser 是否选取所有的雷达
-//    input:select_laser_number_vector 选取的指定雷达id
-//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-Error_manager Laser_manager_task::task_init(Task_statu task_statu,
-											std::string task_statu_information,
-											void* p_tast_receiver,
-											std::chrono::milliseconds task_over_time,
-											unsigned int task_frame_maxnum,
-											bool task_save_flag,
-											std::string task_save_path,
-											std::mutex* p_task_cloud_lock,
-											pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
-											bool select_all_laser_flag,
-											std::vector<int> select_laser_id_vector
-)
-{
-	if(p_task_point_cloud.get() == NULL)
-	{
-		return Error_manager(POINTER_IS_NULL, MINOR_ERROR,
-							 "Laser_task::task_init p_task_point_cloud is null");
-	}
-	if(p_task_cloud_lock==NULL)
-	{
-		return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
-							 "Laser_manager_task::task_init p_task_cloud_lock is null");
-	}
-
-	m_task_statu = task_statu;
-	m_task_statu_information = task_statu_information;
-	mp_tast_receiver = p_tast_receiver;
-	m_task_over_time = task_over_time;
-	m_task_error_manager.error_manager_clear_all();
-
-	m_task_frame_maxnum = task_frame_maxnum;
-	m_task_save_flag = task_save_flag;
-	m_task_save_path = task_save_path;
-	mp_task_cloud_lock=p_task_cloud_lock;
-	mp_task_point_cloud = p_task_point_cloud;
-
-	m_select_all_laser_flag = select_all_laser_flag;
-	m_select_laser_id_vector = select_laser_id_vector;
-
-	return Error_code::SUCCESS;
-}
-
-
-
-//push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
-Error_manager Laser_manager_task::task_push_point(pcl::PointXYZ point_xyz)
-{
-	if(mp_task_cloud_lock==NULL)
-	{
-		return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
-							 "push_point laser task input lock is null");
-	}
-	if(mp_task_point_cloud.get()==NULL)
-	{
-		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
-							 "Laser_task::task_push_point p_task_point_cloud is null");
-	}
-	//加锁,并添加三维点。
-	mp_task_cloud_lock->lock();
-	mp_task_point_cloud->push_back(point_xyz);
-	mp_task_cloud_lock->unlock();
-
-	return SUCCESS;
-}
-
-//把 Laser_manager_task 转化为 Laser_task,注意 task_statu 从外部载入。
-//output:p_laser_task 雷达扫描任务的指针,
-//inpit:task_statu 外部载入的任务状态,默认为 TASK_CREATED
-//inpit:task_over_time 超时时间,一般要比上级任务的时间短一些
-Error_manager Laser_manager_task::trans_to_laser_task(Laser_task * p_laser_task, int laser_index,Laser_base* p_laser_base,
-Task_statu task_statu, std::chrono::milliseconds task_over_time)
-{
-	char t_buf[256] = {0};
-	sprintf(t_buf,"%s/%d", m_task_save_path.c_str(), laser_index);
-
-
-	p_laser_task->task_init(task_statu,
-							m_task_statu_information,
-							p_laser_base,
-							m_task_over_time,
-							m_task_frame_maxnum,
-							m_task_save_flag,
-							t_buf,
-							mp_task_cloud_lock,
-							mp_task_point_cloud
-	);
-	return Error_code::SUCCESS;
-}
-
-
-
-//获取 点云的采集帧数最大值
-unsigned int Laser_manager_task::get_task_frame_maxnum()
-{
-	return m_task_frame_maxnum;
-}
-//获取采集的点云保存文件的使能标志位
-bool Laser_manager_task::get_task_save_flag()
-{
-	return m_task_save_flag;
-}
-//获取采集的点云保存路径
-std::string Laser_manager_task::get_task_save_path()
-{
-	return m_task_save_path;
-}
-//获取 三维点云容器的智能指针
-std::mutex*  Laser_manager_task::get_task_cloud_lock()
-{
-	return mp_task_cloud_lock;
-}
-//获取 三维点云容器的智能指针
-pcl::PointCloud<pcl::PointXYZ>::Ptr Laser_manager_task::get_task_point_cloud()
-{
-	return mp_task_point_cloud;
-}
-
-
-
-//设置 点云的采集帧数最大值
-void Laser_manager_task::set_task_frame_maxnum(unsigned int task_frame_maxnum)
-{
-	m_task_frame_maxnum = task_frame_maxnum;
-
-}
-//设置采集的点云保存文件的使能标志位
-void Laser_manager_task::set_task_save_flag(bool task_save_flag)
-{
-	m_task_save_flag=task_save_flag;
-}
-//设置采集的点云保存路径
-void Laser_manager_task::set_task_save_path(std::string task_save_path)
-{
-	m_task_save_path=task_save_path;
-}
-//设置采集的点云保存标志位和路径
-void Laser_manager_task::set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path)
-{
-	m_task_save_flag=task_save_flag;
-	m_task_save_path=task_save_path;
-}
-
-//获取 是否选取所有的雷达
-bool Laser_manager_task::get_select_all_laser_flag()
-{
-	return m_select_all_laser_flag;
-}
-//设置 是否选取所有的雷达
-void Laser_manager_task::set_select_all_laser_flag( bool select_all_laser_flag)
-{
-	m_select_all_laser_flag = select_all_laser_flag;
-}
-//获取 被选中的雷达编号。
-std::vector<int>& Laser_manager_task::get_select_laser_id_vector()
-{
-	return m_select_laser_id_vector;
-}
-//设置 被选中的雷达编号。
-void Laser_manager_task::set_select_laser_id_vector(std::vector<int>& select_laser_id_vector)
-{
-	m_select_laser_id_vector = select_laser_id_vector;
-}
-
-
-
-
-
-
-

+ 0 - 155
laser/laser_manager_task.h

@@ -1,155 +0,0 @@
-
-/*
- * Laser_manager_task 是雷达管理的任务单。
- * 外部通过它对 Laser_manager 下发任务。
- *
-//用法:上级直接调用 Laser_manager 的接口函数 execute_task ,并将 Laser_manager_task 类作为参数传递
-// Laser_manager 类则按照 Laser_manager_task 的功能码和指定的参数,执行相应的功能
-//并将结果填充到 Laser_manager_task ,返回给上级。
- *
- *
- * */
-
-
-
-
-#ifndef LASER_MANAGER_TASK_H
-#define LASER_MANAGER_TASK_H
-
-#include "Point2D.h"
-#include "Point3D.h"
-#include <pcl/point_types.h>
-#include <pcl/common/common.h>
-#include "../error_code/error_code.h"
-
-#include <vector>
-#include <mutex>
-
-#include "../task/task_command_manager.h"
-#include "../laser/laser_task_command.h"
-#include "../laser/Laser.h"
-
-
-class Laser_manager_task:public Task_Base
-{
-public://API functions
-	//构造函数,构造函数锁定任务类型为 LASER_MANGER_SCAN_TASK ,后续不允许更改
-	Laser_manager_task();
-	Laser_manager_task(const Laser_manager_task& other) = delete;
-	~Laser_manager_task();
-
-	//初始化任务单,必须初始化之后才可以使用,(必选参数)
-	// input:p_task_cloud_lock 三维点云的数据保护锁
-	// output:p_task_point_cloud 三维点云容器的智能指针
-	//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-	Error_manager task_init(std::mutex* p_task_cloud_lock,
-							pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
-
-	//初始化任务单,必须初始化之后才可以使用,(可选参数)
-	//    input:task_statu 任务状态
-	//    input:task_statu_information 状态说明
-	//    input:tast_receiver 接受对象
-	//    input:task_over_time 超时时间
-	//    input:task_frame_maxnum 点云的采集帧数最大值
-	//    input:task_save_flag 是否保存
-	//    input:task_save_path 保存路径
-	//    input:p_task_cloud_lock 三维点云的数据保护锁
-	//    output:p_task_point_cloud 三维点云容器的智能指针
-	//    input:m_is_select_all_laser 是否选取所有的雷达
-	//    input:select_laser_number_vector 选取的指定雷达id
-	//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-	Error_manager task_init(Task_statu task_statu,
-							std::string task_statu_information,
-							void* p_tast_receiver,
-							std::chrono::milliseconds task_over_time,
-							unsigned int task_frame_maxnum,
-							bool task_save_flag,
-							std::string task_save_path,
-							std::mutex* p_task_cloud_lock,
-							pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
-							bool is_select_all_laser,
-							std::vector<int> select_laser_id_vector
-	);
-
-	//push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
-	Error_manager task_push_point(pcl::PointXYZ point_xyz);
-
-	//把 Laser_manager_task 转化为 Laser_task,注意 task_statu 从外部载入。
-	//output:p_laser_task 雷达扫描任务的指针,
-	//inpit:laser_index 雷达编号
-	//inpit:task_statu 外部载入的任务状态,默认为 TASK_CREATED
-	//inpit:task_over_time 超时时间,一般要比上级任务的时间短一些
-	Error_manager trans_to_laser_task(Laser_task * p_laser_task, int laser_index,Laser_base* p_laser_base,
-	Task_statu task_statu = TASK_CREATED,
-									  std::chrono::milliseconds task_over_time = std::chrono::milliseconds(TASK_OVER_TIME_DEFAULT));
-
-public://get or set member variable
-	//获取 点云的采集帧数最大值
-	unsigned int get_task_frame_maxnum();
-	//获取采集的点云保存文件的使能标志位
-	bool get_task_save_flag();
-	//获取采集的点云保存路径
-	std::string get_task_save_path();
-	//获取 三维点云容器的智能指针
-	std::mutex*  get_task_cloud_lock();
-	//获取 三维点云容器的智能指针
-	pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
-
-
-
-	//设置 点云的采集帧数最大值
-	void set_task_frame_maxnum(unsigned int task_frame_maxnum);
-	//设置采集的点云保存文件的使能标志位
-	void set_task_save_flag(bool task_save_flag);
-	//设置采集的点云保存路径
-	void set_task_save_path(std::string task_save_path);
-	//设置采集的点云保存标志位和路径
-	void set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path);
-
-
-
-	//获取 是否选取所有的雷达
-	bool get_select_all_laser_flag();
-	//设置 是否选取所有的雷达
-	void set_select_all_laser_flag( bool select_all_laser_flag);
-	//获取 被选中的雷达编号。
-	std::vector<int>& get_select_laser_id_vector();
-	//设置 被选中的雷达编号。
-	void set_select_laser_id_vector(std::vector<int>& select_laser_id_vector);
-
-protected://member variable
-	//点云的采集帧数最大值,任务输入
-	unsigned int                    m_task_frame_maxnum;
-
-	//雷达保存文件的使能标志位,//默认不保存,false
-	bool		 					m_task_save_flag;
-	//点云保存文件的路径,任务输入
-	std::string                     m_task_save_path;
-
-	//三维点云的数据保护锁,任务输入
-	std::mutex*                     mp_task_cloud_lock;
-	//采集结果,三维点云容器的智能指针,任务输出
-	//这里只是智能指针,实际内存由 任务发送方管理,初始化时必须保证内存有效。
-	pcl::PointCloud<pcl::PointXYZ>::Ptr        mp_task_point_cloud;
-
-
-	bool 							m_select_all_laser_flag;					//是否选取所有的雷达。默认为true
-	std::vector<int>				m_select_laser_id_vector;				//被选中的雷达编号。
-	//注:当 m_is_select_all_laser 为true时,m_select_laser_number_vector不用写。
-	//注:当 m_is_select_all_laser 为false时,m_select_laser_number_vector 必须填写,不能为空。否则报错。
-
-
-
-private:
-
-};
-
-
-
-
-
-
-
-
-
-#endif //LASER_MANAGER_TASK_H

+ 83 - 91
laser/laser_task_command.cpp

@@ -10,16 +10,14 @@
 //构造函数,构造函数锁定任务类型为LASER_TASK,后续不允许更改
 Laser_task::Laser_task()
 {
-    //构造函数锁定任务类型为 LASER_BASE_SCAN_TASK,后续不允许更改
-    m_task_type = LASER_BASE_SCAN_TASK;
+    //构造函数锁定任务类型为LASER_TASK,后续不允许更改
+    m_task_type = LASER_TASK;
     m_task_statu = TASK_CREATED;
-    m_task_statu_information.clear();
-	m_task_error_manager.error_manager_clear_all();
+    //m_task_statu_information默认为空
 
     m_task_frame_maxnum = 0;
-	m_task_save_flag = false;//默认不保存,false
-	m_task_save_path.clear();
     mp_task_point_cloud = NULL;
+    //m_task_error_manager 默认为空
     mp_task_cloud_lock=NULL;
 }
 //析构函数
@@ -29,90 +27,74 @@ Laser_task::~Laser_task()
 }
 
 //初始化任务单,必须初始化之后才可以使用,(必选参数)
-// input:p_task_cloud_lock 三维点云的数据保护锁
+// input:task_statu 任务状态
 // output:p_task_point_cloud 三维点云容器的智能指针
+// input:p_task_cloud_lock 三维点云的数据保护锁
 //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-Error_manager Laser_task::task_init(std::mutex* p_task_cloud_lock,
-											pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud)
+Error_manager Laser_task::task_init(Task_statu task_statu,
+                                    pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                                    std::mutex* p_task_cloud_lock)
 {
-	if(p_task_point_cloud.get() == NULL)
-	{
-		return Error_manager(POINTER_IS_NULL, MINOR_ERROR,
-							 "Laser_task::task_init p_task_point_cloud is null");
-	}
-	if(p_task_cloud_lock==NULL)
-	{
-		return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
-							 "Laser_manager_task::task_init p_task_cloud_lock is null");
-	}
+    if(p_task_point_cloud.get() == NULL)
+    {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "Laser_task::task_init p_task_point_cloud is null");
+    }
+    if(p_task_cloud_lock==NULL)
+    {
+        return Error_manager(POINTER_IS_NULL,MINOR_ERROR,"laser task input lock is null");
+    }
 
-	m_task_statu = TASK_CREATED;
-	m_task_statu_information.clear();
-	m_task_error_manager.error_manager_clear_all();
+    m_task_statu = task_statu;
+    m_task_statu_information.clear();
 
-	m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
-	m_task_save_flag = false;
-	m_task_save_path.clear();
-	mp_task_cloud_lock=p_task_cloud_lock;
-	mp_task_point_cloud = p_task_point_cloud;
+    m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
+    mp_task_cloud_lock=p_task_cloud_lock;
+    mp_task_point_cloud = p_task_point_cloud;
+    m_task_error_manager.error_manager_clear_all();
 
-	return Error_code::SUCCESS;
+    return Error_code::SUCCESS;
 }
 
 //初始化任务单,必须初始化之后才可以使用,(可选参数)
-//    input:task_statu 任务状态
-//    input:task_statu_information 状态说明
-//    input:tast_receiver 接受对象
-//    input:task_over_time 超时时间
-//    input:task_frame_maxnum 点云的采集帧数最大值
-//    input:task_save_flag 是否保存
-//    input:task_save_path 保存路径
-//    input:p_task_cloud_lock 三维点云的数据保护锁
-//    output:p_task_point_cloud 三维点云容器的智能指针
+//    input:task_statu任务状态
+//    input:task_statu_information状态说明
+//    input:task_frame_maxnum点云的采集帧数最大值
+//    output:p_task_point_cloud三维点云容器的智能指针
+// input:p_task_cloud_lock 三维点云的数据保护锁
 //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
 Error_manager Laser_task::task_init(Task_statu task_statu,
-											std::string task_statu_information,
-											void* p_tast_receiver,
-											std::chrono::milliseconds task_over_time,
-											unsigned int task_frame_maxnum,
-											bool task_save_flag,
-											std::string task_save_path,
-											std::mutex* p_task_cloud_lock,
-											pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud
-)
-{
-	if(p_task_point_cloud.get() == NULL)
-	{
-		return Error_manager(POINTER_IS_NULL, MINOR_ERROR,
-							 "Laser_task::task_init p_task_point_cloud is null");
-	}
-	if(p_task_cloud_lock==NULL)
-	{
-		return Error_manager(POINTER_IS_NULL,MINOR_ERROR,
-							 "Laser_manager_task::task_init p_task_cloud_lock is null");
-	}
-
-	m_task_statu = task_statu;
-	m_task_statu_information = task_statu_information;
-	mp_tast_receiver = p_tast_receiver;
-	m_task_over_time = task_over_time;
-	m_task_error_manager.error_manager_clear_all();
-
-	if ( task_frame_maxnum == 0 )
-	{
-		m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
-	}
-	else
-	{
-		m_task_frame_maxnum = task_frame_maxnum;
-	}
-
-	m_task_save_flag = task_save_flag;
-	m_task_save_path = task_save_path;
-	mp_task_cloud_lock=p_task_cloud_lock;
-	mp_task_point_cloud = p_task_point_cloud;
-
-	return Error_code::SUCCESS;
+                                    std::string & task_statu_information,
+                                    unsigned int task_frame_maxnum,
+                                    pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                                    std::mutex* p_task_cloud_lock)
+{
+    if(p_task_point_cloud.get() == NULL)
+    {
+        return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+                             "Laser_task::task_init p_task_point_cloud is null");
+    }
+    if(p_task_cloud_lock==NULL)
+    {
+        return Error_manager(POINTER_IS_NULL,MINOR_ERROR,"laser task input lock is null");
+    }
+
+    m_task_statu = task_statu;
+    m_task_statu_information = task_statu_information;
+
+    if(task_frame_maxnum == 0)
+    {
+        m_task_frame_maxnum = TASK_FRAME_MAXNUM_DEFAULT;
+    }
+    else
+    {
+        m_task_frame_maxnum = task_frame_maxnum;
+    }
+    mp_task_cloud_lock=p_task_cloud_lock;
+    mp_task_point_cloud = p_task_point_cloud;
+    m_task_error_manager.error_manager_clear_all();
+
+    return Error_code::SUCCESS;
 }
 
 //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
@@ -141,7 +123,7 @@ Error_manager Laser_task::task_push_point(pcl::PointXYZ point_xyz)
 //获取 点云的采集帧数最大值
 unsigned int Laser_task::get_task_frame_maxnum()
 {
-    return m_task_frame_maxnum;
+	return m_task_frame_maxnum;
 }
 //获取采集的点云保存文件的使能标志位
 bool Laser_task::get_task_save_flag()
@@ -151,7 +133,7 @@ bool Laser_task::get_task_save_flag()
 //获取采集的点云保存路径
 std::string Laser_task::get_task_save_path()
 {
-    return m_task_save_path;
+	return m_task_save_path;
 }
 //获取 三维点云容器的智能指针
 std::mutex*  Laser_task::get_task_cloud_lock()
@@ -161,35 +143,45 @@ std::mutex*  Laser_task::get_task_cloud_lock()
 //获取 三维点云容器的智能指针
 pcl::PointCloud<pcl::PointXYZ>::Ptr Laser_task::get_task_point_cloud()
 {
-    return mp_task_point_cloud;
+	return mp_task_point_cloud;
 }
 
 
 
 
+//设置 任务状态
+void Laser_task::set_task_statu(Task_statu task_statu)
+{
+    m_task_statu = task_statu;
+}
+//设置 任务状态说明
+void Laser_task::set_task_statu_information(std::string & task_statu_information)
+{
+    m_task_statu_information = task_statu_information;
+}
 //设置 点云的采集帧数最大值
 void Laser_task::set_task_frame_maxnum(unsigned int task_frame_maxnum)
 {
     m_task_frame_maxnum = task_frame_maxnum;
 
 }
-//设置采集的点云保存文件的使能标志位
-void Laser_task::set_task_save_flag(bool task_save_flag)
-{
-	m_task_save_flag=task_save_flag;
-}
 //设置采集的点云保存路径
 void Laser_task::set_task_save_path(std::string task_save_path)
 {
     m_task_save_path=task_save_path;
 }
-//设置采集的点云保存标志位和路径
-void Laser_task::set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path)
+//设置 三维点云容器的智能指针
+void Laser_task::set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud)
+{
+    mp_task_point_cloud = p_task_point_cloud;
+}
+//设置 错误码
+void Laser_task::set_task_error_manager(Error_manager & error_manager)
 {
-	m_task_save_flag=task_save_flag;
-	m_task_save_path=task_save_path;
+    m_task_error_manager = error_manager;
 }
 
 
 
 
+

+ 46 - 52
laser/laser_task_command.h

@@ -33,81 +33,75 @@ public:
     //析构函数
     ~Laser_task();
 
-	//初始化任务单,必须初始化之后才可以使用,(必选参数)
-	// input:p_task_cloud_lock 三维点云的数据保护锁
-	// output:p_task_point_cloud 三维点云容器的智能指针
-	//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-	Error_manager task_init(std::mutex* p_task_cloud_lock,
-							pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
-
-	//初始化任务单,必须初始化之后才可以使用,(可选参数)
-	//    input:task_statu 任务状态
-	//    input:task_statu_information 状态说明
-	//    input:tast_receiver 接受对象
-	//    input:task_over_time 超时时间
-	//    input:task_frame_maxnum 点云的采集帧数最大值
-	//    input:task_save_flag 是否保存
-	//    input:task_save_path 保存路径
-	//    input:p_task_cloud_lock 三维点云的数据保护锁
-	//    output:p_task_point_cloud 三维点云容器的智能指针
-	//注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
-	Error_manager task_init(Task_statu task_statu,
-							std::string task_statu_information,
-							void* p_tast_receiver,
-							std::chrono::milliseconds task_over_time,
-							unsigned int task_frame_maxnum,
-							bool task_save_flag,
-							std::string task_save_path,
-							std::mutex* p_task_cloud_lock,
-							pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud
-	);
+    //初始化任务单,必须初始化之后才可以使用,(必选参数)
+    // input:task_statu 任务状态
+    // output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
+
+    //初始化任务单,必须初始化之后才可以使用,(可选参数)
+    //    input:task_statu任务状态
+    //    input:task_statu_information状态说明
+    //    input:task_frame_maxnum点云的采集帧数最大值
+    //    output:p_task_point_cloud 三维点云容器的智能指针
+    // input:p_task_cloud_lock 三维点云的数据保护锁
+    //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
+    Error_manager task_init(Task_statu task_statu,
+                            std::string & task_statu_information,
+                            unsigned int task_frame_maxnum,
+                            pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud,
+                            std::mutex* p_task_cloud_lock);
 
     //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
     Error_manager task_push_point(pcl::PointXYZ point_xyz);
 
 
 public:
-    //获取 点云的采集帧数最大值
-    unsigned int get_task_frame_maxnum();
+	//获取 点云的采集帧数最大值
+	unsigned int get_task_frame_maxnum();
 	//获取采集的点云保存文件的使能标志位
 	bool get_task_save_flag();
-    //获取采集的点云保存路径
-    std::string get_task_save_path();
+	//获取采集的点云保存路径
+	std::string get_task_save_path();
 	//获取 三维点云容器的智能指针
 	std::mutex*  get_task_cloud_lock();
-    //获取 三维点云容器的智能指针
-    pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
-
+	//获取 三维点云容器的智能指针
+	pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
 
 
 
 
+    //设置 任务状态
+    void set_task_statu(Task_statu task_statu);
+    //设置 任务状态说明
+    void set_task_statu_information(std::string & task_statu_information);
     //设置 点云的采集帧数最大值
     void set_task_frame_maxnum(unsigned int task_frame_maxnum);
-	//设置采集的点云保存文件的使能标志位
-	void set_task_save_flag(bool task_save_flag);
-	//设置采集的点云保存路径
+    //设置采集的点云保存路径
     void set_task_save_path(std::string task_save_path);
-	//设置采集的点云保存标志位和路径
-	void set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path);
-
-
+    //设置 三维点云容器的智能指针
+    void set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
+    //设置 错误码
+    void set_task_error_manager(Error_manager & error_manager);
 
 
 protected:
-    //点云的采集帧数最大值,任务输入
-    unsigned int                    m_task_frame_maxnum;
+	//点云的采集帧数最大值,任务输入
+	unsigned int                    m_task_frame_maxnum;
 
 	//雷达保存文件的使能标志位,//默认不保存,false
 	bool		 					m_task_save_flag;
-    //点云保存文件的路径,任务输入
-    std::string                     m_task_save_path;
-
-    //三维点云的数据保护锁,任务输入
-    std::mutex*                     mp_task_cloud_lock;
-    //采集结果,三维点云容器的智能指针,任务输出
-    //这里只是智能指针,实际内存由任务发送方管理管理,初始化时必须保证内存有效。
-    pcl::PointCloud<pcl::PointXYZ>::Ptr        mp_task_point_cloud;
+	//点云保存文件的路径,任务输入
+	std::string                     m_task_save_path;
+
+	//三维点云的数据保护锁,任务输入
+	std::mutex*                     mp_task_cloud_lock;
+	//采集结果,三维点云容器的智能指针,任务输出
+	//这里只是智能指针,实际内存由任务发送方管理管理,初始化时必须保证内存有效。
+	pcl::PointCloud<pcl::PointXYZ>::Ptr        mp_task_point_cloud;
 
 
 };

+ 6 - 39
locate/point_sift_segmentation.cpp

@@ -2,13 +2,6 @@
 #include <glog/logging.h>
 #include <fstream>
 
-
-#include <time.h>
-#include <sys/time.h>
-#include <chrono>
-using namespace std;
-using namespace chrono;
-
 void save_rgb_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZRGB>& pCloud)
 {
 	std::ofstream os;
@@ -62,9 +55,6 @@ Error_manager Point_sift_segmentation::init(std::string graph, std::string cpkt)
     //创建空数据,第一次初始化后空跑
 	float* cloud_data = (float*)malloc(m_point_num * 3 * sizeof(float));
 	float* output = (float*)malloc(m_point_num * m_cls_num * sizeof(float));
-
-	auto start   = system_clock::now();
-
 	if (false == Predict(cloud_data, output))
 	{
 		free(cloud_data);
@@ -79,12 +69,6 @@ Error_manager Point_sift_segmentation::init(std::string graph, std::string cpkt)
 		free(output);
 
 	}
-	auto end   = system_clock::now();
-	auto duration = duration_cast<microseconds>(end - start);
-	cout <<  "花费了"
-		 << double(duration.count()) * microseconds::period::num / microseconds::period::den   << "秒" << endl;
-
-
 	return SUCCESS;
 }
 
@@ -153,7 +137,7 @@ bool Point_sift_segmentation::Create_data(pcl::PointCloud<pcl::PointXYZ>::Ptr cl
 
 	if (cloud_select->points.size() != m_point_num)
 	{
-//		LOG(ERROR) << "\tpointSIFT input select cloud is not " << m_point_num;
+		LOG(ERROR) << "\tpointSIFT input select cloud is not " << m_point_num;
 		return false;
 	}
 
@@ -178,7 +162,7 @@ Error_manager Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr c
 	float* output = (float*)malloc(m_point_num*m_cls_num*sizeof(float));
 	memset(data, 0, m_point_num * 3 * sizeof(float));
 	memset(output, 0, m_point_num*m_cls_num * sizeof(float));
-	//LOG(INFO) << "cloud size:" << cloud->size()<<"  /  "<<m_point_num;
+	LOG(INFO) << "cloud size:" << cloud->size()<<"  /  "<<m_point_num;
 	if (!Create_data(cloud, data))
 	{
 		free(data);
@@ -186,29 +170,12 @@ Error_manager Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr c
 		return Error_manager(LOCATER_SIFT_CREATE_INPUT_DATA_FAILED,NORMAL,"pointSIFT Create input data ERROR");
 	}
 
-//	for (int i = 0; i < m_point_num; ++i)
-//	{
-//		pcl::PointXYZ point = cloud->points[i];
-//		*(data + i * 3) = point.x;
-//		*(data + i * 3+1) = point.y ;
-//		*(data + i * 3+2) = point.z ;
-//	}
-
-	auto start = system_clock::now();
-
 	if (!Predict(data, output))
 	{
 		free(data);
 		free(output);
 		return Error_manager(LOCATER_SIFT_PREDICT_FAILED,NORMAL,"pointSIFT predict ERROR");
 	}
-	auto end   = system_clock::now();
-	auto duration = duration_cast<microseconds>(end - start);
-	cout <<  "花费了"
-		 << double(duration.count()) * microseconds::period::num / microseconds::period::den   << "秒" << endl;
-	cout <<  double(duration.count()) << " "
-		 <<   microseconds::period::num << " " << microseconds::period::den   << "秒" << endl;
-
 	////������
 	RecoveryCloud(output, data, cloud_seg);
 	if (!FilterObs(cloud_seg,save_dir))
@@ -231,7 +198,7 @@ Error_manager Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr c
 	{
 		seg->operator +=(*cloud_seg[i]);
 	}
-	std::cout << "huli_test seg_size = " << seg->points.size() << std::endl;
+
 	static int count = 0;
 	count = (count + 1) % m_cls_num;
 	char buf[64] = { 0 };
@@ -255,9 +222,9 @@ bool Point_sift_segmentation::RecoveryCloud(float* output, float* cloud, std::ve
 	for (int i = 0; i < m_point_num; ++i)
 	{
 		pcl::PointXYZ point;
-		point.x = *(cloud + i * 3)+center.x;
-		point.y = *(cloud + i * 3 + 1)+center.y;
-		point.z = *(cloud + i * 3 + 2);
+		point.x = *(cloud + i * 3)*1000.+center.x;
+		point.y = *(cloud + i * 3 + 1)*1000.+center.y;
+		point.z = *(cloud + i * 3 + 2)*1000.;
 		if (point.x > m_maxp.x || point.x<m_minp.x
 			|| point.y>m_maxp.y || point.y<m_minp.y
 			|| point.z>m_maxp.z || point.z < m_minp.z)

+ 82 - 120
main.cpp

@@ -1,22 +1,17 @@
 //
 // Created by zx on 2019/12/28.
 //
+#include <fcntl.h>
 #include <iostream>
+#include "plc/plc_communicator.h"
+#include "laser/Laser.h"
+#include "plc/plc_communicator.h"
+#include "locate/locater.h"
+#include "terminor/terminal_command_executor.h"
+#include "system_manager/System_Manager.h"
+#include "tool/pathcreator.h"
+#include <glog/logging.h>
 
-#include "./laser/laser_manager.h"
-#include "./laser/Laser.h"
-#include "./laser/LivoxLaser.h"
-#include "./locate/point_sift_segmentation.h"
-#include <iostream>
-#include <fstream>
-
-#include "./error_code/error_code.h"
-#include "LogFiles.h"
-#include <string.h>
-#include <fcntl.h>
-#include <google/protobuf/io/zero_copy_stream_impl.h>
-#include <google/protobuf/text_format.h>
-//#include </usr/local/include/google/protobuf/io/zero_copy_stream_impl.h>
 using google::protobuf::io::FileInputStream;
 using google::protobuf::io::FileOutputStream;
 using google::protobuf::io::ZeroCopyInputStream;
@@ -24,116 +19,83 @@ using google::protobuf::io::CodedInputStream;
 using google::protobuf::io::ZeroCopyOutputStream;
 using google::protobuf::io::CodedOutputStream;
 using google::protobuf::Message;
+GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
+{
+    time_t tt;
+    time( &tt );
+    tt = tt + 8*3600;  // transform the time zone
+    tm* t= gmtime( &tt );
+    char buf[255]={0};
+    sprintf(buf,"./%d%02d%02d-%02d%02d%02d-dump.txt",
+            t->tm_year + 1900,
+            t->tm_mon + 1,
+            t->tm_mday,
+            t->tm_hour,
+            t->tm_min,
+            t->tm_sec);
+
+    FILE* tp_file=fopen(buf,"w");
+    fprintf(tp_file,data,strlen(data));
+    fclose(tp_file);
 
-#define O_RDONLY	     00
-
-#define LIVOX_NUMBER	     2
+}
 
-//读取protobuf 配置文件
-//file:文件
-//parameter:要读取的配置
-bool read_proto_param(std::string file, ::google::protobuf::Message& parameter)
+void init_glog()
 {
-	int fd = open(file.c_str(), O_RDONLY);
-	if (fd == -1) return false;
-	FileInputStream* input = new FileInputStream(fd);
-	bool success = google::protobuf::TextFormat::Parse(input, &parameter);
-	delete input;
-	close(fd);
-	return success;
+    time_t tt = time(0);//时间cuo
+    struct tm* t = localtime(&tt);
+
+    char strYear[255]={0};
+    char strMonth[255]={0};
+    char strDay[255]={0};
+
+    sprintf(strYear,"%04d", t->tm_year+1900);
+    sprintf(strMonth,"%02d", t->tm_mon+1);
+    sprintf(strDay,"%02d", t->tm_mday);
+
+    char buf[255]={0};
+    getcwd(buf,255);
+    char strdir[255]={0};
+    sprintf(strdir,"%s/log/%s/%s/%s", buf,strYear,strMonth,strDay);
+    PathCreator creator;
+    creator.Mkdir(strdir);
+
+    char logPath[255] = { 0 };
+    sprintf(logPath, "%s/", strdir);
+    FLAGS_max_log_size = 100;
+    FLAGS_logbufsecs = 0;
+    google::InitGoogleLogging("LidarMeasurement");
+    google::SetStderrLogging(google::INFO);
+    google::SetLogDestination(0, logPath);
+    google::SetLogFilenameExtension("zxlog");
+    google::InstallFailureSignalHandler();
+    google::InstallFailureWriter(&shut_down_logging);
+    FLAGS_colorlogtostderr = true;        // Set log color
+    FLAGS_logbufsecs = 0;                // Set log output speed(s)
+    FLAGS_max_log_size = 1024;            // Set max log file size(GB)
+    FLAGS_stop_logging_if_full_disk = true;
 }
 
-
-
 int main(int argc,char* argv[])
 {
-	Error_manager err;
-	Error_manager code ;
-
-	std::cout << "huli 101 main start!" << std::endl;
-
-	Laser_manager * tp_laser_manager = Laser_manager::get_instance_pointer();
-	tp_laser_manager->laser_manager_init();
-
-
-	Point_sift_segmentation*                mp_point_sift;
-	int point_size = 8192;
-	int cls_num = 3;
-	double freq = 20.0;
-	std::string graph = "../model_param/seg_model_404500.ckpt.meta";
-	std::string cpkt = "../model_param/seg_model_404500.ckpt";
-	pcl::PointXYZ minp(-10000,-10000,-10000);
-	pcl::PointXYZ maxp(10000,10000,10000);
-
-
-
-
-	while(1)
-	{
-		pcl::PointCloud<pcl::PointXYZ>::Ptr scan_cloud(new pcl::PointCloud<pcl::PointXYZ>);
-		std::mutex cloud_lock;
-		std::vector<int> select_laser_id_vector;
-
-		Laser_manager_task * laser_manager_task = new Laser_manager_task;
-		laser_manager_task->task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(15000),
-									  1000,true,"../data/laser_data",&cloud_lock,scan_cloud,
-									  true,select_laser_id_vector	);
-
-
-
-		std::cout << "huli 401 connect_laser Error_code::SUCCESS" << std::endl;
-
-		std::cout << " press to start" << std::endl;
-		char ch ;
-//		= getchar();
-
-		std::this_thread::sleep_for(std::chrono::seconds(2));
-		std::cin >> ch ;
-
-		if ( ch == 'b' )
-		{
-			std::cout << "  end scan ------------" << std::endl;
-			break;
-		}
-		std::cout << "  start scan ------------" << std::endl;
-
-		int n = 1;
-		while(n)
-		{
-			n--;
-
-			task_command_manager::get_instance_references().execute_task(laser_manager_task);
-//			tp_laser_manager->execute_task(laser_manager_task);
-
-			usleep(5000 * 1000);
-			cout << "huli: 501 :" << err.to_string() << endl;
-			cout << "huli: 501 :" << err.to_string() << endl;
-		}
-
-		cout << "huli: 601 :" << err.to_string() << endl;
-		//发送任务单给雷达
-		std::this_thread::sleep_for(std::chrono::seconds(2));
-
-		delete(laser_manager_task);
-
-
-		//locate
-		pcl::getMinMax3D(*scan_cloud,minp,maxp);
-		std::cout << "huli 112" << std::endl;
-		mp_point_sift = new Point_sift_segmentation(point_size,cls_num,freq,minp,maxp);
-		std::cout << code.to_string() << std::endl;
-
-		code = mp_point_sift->init(graph,cpkt);
-		std::cout << code.to_string() << std::endl;
-
-		std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> segmentation_clouds;
-		code = mp_point_sift->seg(scan_cloud, segmentation_clouds, "../data/locate_data");
-		std::cout << code.to_string() << std::endl;
-
-	}
-
-	tp_laser_manager->laser_manager_uninit();
-	cout << "huli 1234 main end" << endl;
-}
-
-
+    Error_manager code;
+    //初始化日志
+    init_glog();
+    //创建system实例
+    System_Manager system_manager;
+    //初始化实例,包括雷达,plc,locater,terminal的创建及初始化
+    code=system_manager.init();
+    if(code!=SUCCESS)
+    {
+        LOG(ERROR)<<code.to_string();
+        printf("print ctrl-c to quite");
+    }
+    else
+    {
+        LOG(INFO)<<"SYSTEM Init OK !!!!";
+    }
+
+    getchar();
+
+    return 0;
+}

+ 0 - 42
setting/laser.prototxt

@@ -1,42 +0,0 @@
-#1号雷达
-#0TFDFG700601881
-
-
-laser_parameters
-{
-	type:"Livox"
-	sn:"0TFDFCE00502001"
-	frame_num:1000
-    mat_r00:1
-    mat_r01:0
-    mat_r02:0
-    mat_r03:0
-    mat_r10:0
-    mat_r11:1
-    mat_r12:0
-    mat_r13:0
-    mat_r20:0
-    mat_r21:0
-    mat_r22:1
-    mat_r23:0
-}
-
-
-laser_parameters
-{
-	type:"Livox"
-	sn:"0TFDFG700601881"
-	frame_num:1000
-    mat_r00:1
-    mat_r01:0
-    mat_r02:0
-    mat_r03:0
-    mat_r10:0
-    mat_r11:1
-    mat_r12:0
-    mat_r13:0
-    mat_r20:0
-    mat_r21:0
-    mat_r22:1
-    mat_r23:0
-}

+ 0 - 110
task/task_base.cpp

@@ -1,110 +0,0 @@
-//
-// Created by zx on 2019/12/28.
-//
-
-#include "task_base.h"
-#include "../error_code/error_code.h"
-
-Task_Base::Task_Base()
-{
-    m_task_type = UNKNOW_TASK;
-	m_task_statu = TASK_CREATED;
-	mp_tast_receiver = NULL;
-
-	m_task_start_time = std::chrono::system_clock::now();	//获取当前时间
-	m_task_over_time = std::chrono::milliseconds(TASK_OVER_TIME_DEFAULT); //默认10秒
-}
-Task_Base::~Task_Base()
-{
-	mp_tast_receiver = NULL;
-}
-
-
-//更新任务单
-//task_statu: 任务状态
-//statu_information:状态说明
-Error_manager Task_Base::update_statu(Task_statu task_statu,std::string statu_information)
-{
-    m_task_statu=task_statu;
-    m_task_statu_information=statu_information;
-    return SUCCESS;
-}
-
-//判断是否超时。返回true表示任务超时,返回false表示任务没有超时
-bool Task_Base::is_over_time()
-{
-	return (std::chrono::system_clock::now() - m_task_start_time) > m_task_over_time;
-}
-
-
-
-//获取任务类型
-Task_type Task_Base::get_task_type()
-{
-    return m_task_type;
-}
-//获取任务单状态
-Task_statu  Task_Base::get_task_statu()
-{
-    return m_task_statu;
-}
-//设置 任务单状态
-void  Task_Base::set_task_statu(Task_statu task_statu)
-{
-	m_task_statu = task_statu;
-}
-//获取状态说明
-std::string Task_Base::get_task_statu_information()
-{
-    return m_task_statu_information;
-}
-//设置 状态说明
-void Task_Base::set_task_statu_information(std::string task_statu_information)
-{
-	m_task_statu_information = task_statu_information;
-}
-//获取 错误码,返回引用。
-Error_manager& Task_Base::get_task_error_manager()
-{
-	return m_task_error_manager;
-}
-//设置 错误码
-void Task_Base::set_task_error_manager(Error_manager & error_manager)
-{
-	m_task_error_manager = error_manager;
-}
-//获取任务接收方
-void * Task_Base::get_tast_receiver()
-{
-	return mp_tast_receiver;
-}
-//设置任务接收方
-void Task_Base::set_tast_receiver(void * p_tast_receiver)
-{
-	mp_tast_receiver = p_tast_receiver;
-}
-
-
-//获取 任务创建的时间点
-std::chrono::system_clock::time_point Task_Base::get_task_start_time()
-{
-	return m_task_start_time;
-}
-//设置 任务创建的时间点
-void Task_Base::set_task_start_time(std::chrono::system_clock::time_point task_start_time)
-{
-	m_task_start_time = task_start_time;
-}
-//获取 任务超时的时限
-std::chrono::milliseconds	Task_Base::get_task_over_time()
-{
-	return m_task_over_time;
-}
-//设置 任务超时的时限
-void	Task_Base::get_task_over_time(std::chrono::milliseconds task_over_time)
-{
-	m_task_over_time = task_over_time;
-}
-
-
-

+ 0 - 107
task/task_base.h

@@ -1,107 +0,0 @@
-/*
- * Task_Base 是任务基类,用作不同的模块之间的通信载体。
- *	每一个模块创建一个任务子类,从Task_Base继承。
- *	然后任务子类自定义一些数据和读写数据的接口函数。
- *	然后在任务接受方实现 execute_task(Task_Base* p_laser_task)
- * */
-
-#ifndef TASK_BASE_H
-#define TASK_BASE_H
-#include <string>
-#include "../error_code/error_code.h"
-#include <chrono>
-
-//任务超时时间默认值10000ms,10秒
-#define TASK_OVER_TIME_DEFAULT				10000
-
-//任务类型
-enum Task_type
-{
-	UNKNOW_TASK             =0,				//未知任务单//初始化,默认值
-	LASER_MANGER_SCAN_TASK  =1,             //雷达管理模块的扫描任务,
-	LASER_BASE_SCAN_TASK    =2,             //单个雷达的扫描任务,
-    LOCATE_TASK             =3,             //测量任务
-    PLC_TASK                =4,             //上传PLC任务
-
-    WJ_TASK,
-    
-};
-//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
-enum Task_statu
-{
-    TASK_CREATED            =0,             //创建状态,默认值
-    TASK_SIGNED             =1,             //已签收
-    TASK_WORKING            =2,             //处理中
-    TASK_OVER               =3,             //已结束
-
-	TASK_ERROR              =11,             //任务错误
-	TASK_DEAD               =12,             //任务死亡,需要销毁
-
-};
-
-//任务单基类
-class Task_Base
-{
-protected:
-	//不允许构造基类,只允许子类构造,(多态)
-	Task_Base();
-public:
-    ~Task_Base();
-
-    //更新任务单
-    //task_statu: 任务状态
-    //statu_information:状态说明
-    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
-
-    //判断是否超时。返回true表示任务超时,返回false表示任务没有超时
-    bool is_over_time();
-
-public:
-    //获取 任务类型
-    Task_type   get_task_type();
-	//设置 任务类型
-//	void   set_task_type(Task_type task_type) = delete;
-    //获取 任务单状态
-    Task_statu  get_task_statu();
-	//设置 任务单状态
-	void  set_task_statu(Task_statu task_statu);
-    //获取 状态说明
-    std::string get_task_statu_information();
-	//设置 状态说明
-	void set_task_statu_information(std::string task_statu_information);
-	//获取 错误码,返回引用。
-	Error_manager& get_task_error_manager();
-	//设置 错误码
-	void set_task_error_manager(Error_manager & error_manager);
-
-	//获取任务接收方
-	void * get_tast_receiver();
-	//设置任务接收方
-	void set_tast_receiver(void * p_tast_receiver);
-	//获取 任务创建的时间点
-	std::chrono::system_clock::time_point get_task_start_time();
-	//设置 任务创建的时间点
-	void set_task_start_time(std::chrono::system_clock::time_point task_start_time);
-	//获取 任务超时的时限
-	std::chrono::milliseconds	get_task_over_time();
-	//设置 任务超时的时限
-	void	get_task_over_time(std::chrono::milliseconds task_over_time);
-
-
-protected:
-    Task_type                   m_task_type;					//任务类型,不允许中途修改
-    Task_statu                  m_task_statu;					//任务状态
-    std::string					m_task_statu_information;		//任务状态说明
-    void*						mp_tast_receiver;				//任务接收方,Task_Base并不分配和释放内存。
-    //注:mp_tast_receiver是可选的,可以为NULL。如果为NULL,则需要task_command_manager去找到接收对象。
-
-	std::chrono::system_clock::time_point 	m_task_start_time;	//任务创建的时间点
-	std::chrono::milliseconds	m_task_over_time;				//任务超时的时限
-	//注:std::chrono::system_clock::now();	//获取当前时间
-
-	//错误码,任务故障信息,任务输出
-	Error_manager               m_task_error_manager;
-};
-
-#endif //TASK_BASE_H
-

+ 0 - 80
task/task_base.puml

@@ -1,80 +0,0 @@
-@startuml
-@startuml
-skinparam classAttributeIconSize 0
-
-
-title  Task_Base 任务单基类
-
-
-
-
-enum Task_type
-{
-//任务类型
-	UNKNOW_TASK             =0,				//未知任务单//初始化,默认值
-	LASER_TASK              =1,             //雷达扫描任务,
-    LOCATE_TASK             =2,             //测量任务
-    PLC_TASK                =3,             //上传PLC任务
-}
-
-
-enum Task_statu
-{
-//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
-    TASK_CREATED            =0,             //创建状态,默认值
-    TASK_SIGNED             =1,             //已签收
-    TASK_WORKING            =2,             //处理中
-    TASK_OVER               =3,             //已结束
-}
-
-
-
-
-class Task_Base
-{
-//任务单基类
-==public:==
-    ~Task_Base();
-..
-    //初始化任务单,初始任务单类型为 UNKONW_TASK
-    virtual Error_manager init();
-..
-    //更新任务单
-    //task_statu: 任务状态
-    //statu_information:状态说明
-    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
-..
-    //获取任务类型
-    Task_type   get_task_type();
-..
-    //获取任务单状态
-    Task_statu  get_statu();
-..
-    //获取状态说明
-    std::string get_statu_information();
-..
-	//获取 错误码
-	Error_manager& get_task_error_manager();
-..
-	//设置 错误码
-	void set_task_error_manager(Error_manager & error_manager);
-==protected:==
-    Task_Base();
-==protected:==
-    Task_type                   m_task_type;                    //任务类型
-    Task_statu                  m_task_statu;                   //任务状态
-    std::string                 m_task_statu_information;       //任务状态说明
-	//错误码,任务故障信息,任务输出
-	Error_manager               m_task_error_manager;
-}
-
-class Error_manager
-{
-//错误码管理
-}
-Task_Base <-- Error_manager : include
-
-
-Task_Base <-- Task_type : include
-Task_Base <-- Task_statu : include
-@enduml

+ 49 - 66
task/task_command_manager.cpp

@@ -1,76 +1,59 @@
-
-
+//
+// Created by zx on 2019/12/28.
+//
 
 #include "task_command_manager.h"
-#include "../laser/Laser.h"
-#include "../laser/laser_manager.h"
-
+#include "../error.h"
 
-//对外的接口函数,所有的任务发送方,都必须使用该函数。
-//execute_task在内部解析了Task_Base里面的Task_type,然后转发给具体某个模块的实例对象。
-//input:p_task_base 任务单,基类的指针,指向子类的实例,(多态)
-Error_manager task_command_manager::execute_task(Task_Base* p_task_base)
+Task_Base::Task_Base()
 {
-	Error_manager t_error;
-	void * tp_tast_receiver = p_task_base->get_tast_receiver();
-	switch ( p_task_base->get_task_type() )
-	{
-	    case UNKNOW_TASK:
-			t_error.error_manager_reset(Error_code::TASK_TYPE_IS_UNKNOW, Error_level::MINOR_ERROR,
-								" p_task_base->get_task_type() is  UNKNOW_TASK ");
-	        break;
-		case LASER_MANGER_SCAN_TASK:
-			if ( tp_tast_receiver != NULL )
-			{
-				((Laser_manager*)tp_tast_receiver)->execute_task(p_task_base);
-			}
-			else
-			{
-				Laser_manager::get_instance_references().execute_task(p_task_base);
-			}
-			break;
-		case LASER_BASE_SCAN_TASK:
-			if ( tp_tast_receiver != NULL )
-			{
-				((Laser_base*)tp_tast_receiver)->execute_task(p_task_base);
-			}
-			else
-			{
-				return Error_manager(Error_code::ERROR, Error_level::MINOR_ERROR,
-									" fun error ");
-	        }
-	        break;
-		case LOCATE_TASK:
-			;
-			break;
-		case PLC_TASK:
-			;
-			break;
-		case WJ_TASK:
-			;
-			break;
-	    default:
-
-	        break;
-	}
-
-	return t_error;
+    m_task_type=UNKNOW_TASK;
 }
+Task_Base::~Task_Base()
+{
 
+}
+//初始化任务单,初始任务单类型为 UNKONW_TASK
+Error_manager Task_Base::init()
+{
+    m_task_type=UNKNOW_TASK;
+    return SUCCESS;
+}
+//更新任务单
+//task_statu: 任务状态
+//statu_information:状态说明
+Error_manager Task_Base::update_statu(Task_statu task_statu,std::string statu_information)
+{
+    m_task_statu=task_statu;
+    m_task_statu_information=statu_information;
+    return SUCCESS;
+}
+//获取任务类型
+Task_type Task_Base::get_task_type()
+{
+    return m_task_type;
+}
+//获取任务单状态
+Task_statu  Task_Base::get_statu()
+{
+    return m_task_statu;
+}
+//获取状态说明
+std::string Task_Base::get_statu_information()
+{
+    return m_task_statu_information;
+}
 
-
-
-
-
-
-
-
-
-
-
-
-
-
+//获取 错误码
+Error_manager& Task_Base::get_task_error_manager()
+{
+	return m_task_error_manager;
+}
+//设置 错误码
+void Task_Base::set_task_error_manager(Error_manager & error_manager)
+{
+	m_task_error_manager = error_manager;
+}
 
 
 

+ 47 - 30
task/task_command_manager.h

@@ -1,42 +1,59 @@
-/*
- * task_command_manager 是任务单的总管理,单例模式
- * 负责管理任务单的派送和转发
- * 所有的任务发送方都只需要调用 task_command_manager.get_instance_references().execute_task(p_task_base)
- * 然后task_command_manager去找到对应的接受对象,来调用该对象的接口函数。 例如Laser_base::execute_task
- * 这样发送方和接收方不直接绑定,双方完全独立。
- * 没有在实例里面保存对方的回调函数或者对象指针
- *
- * */
+//
+// Created by zx on 2019/12/28.
+//
 
 #ifndef TASK_COMAND_MANAGER_H
 #define TASK_COMAND_MANAGER_H
 #include <string>
 #include "../error_code/error_code.h"
-#include "../task/task_base.h"
-#include "../tool/singleton.h"
 
-
-class task_command_manager:public Singleton<task_command_manager>
+//任务类型
+enum Task_type
 {
-// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-	friend class Singleton<task_command_manager>;
-public:
-// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
-	task_command_manager(const task_command_manager&)=delete;
-	task_command_manager& operator =(const task_command_manager&)= delete;
-	~task_command_manager()=default;
-private:
-// 父类的构造函数必须保护,子类的构造函数必须私有。
-	task_command_manager()=default;
+    LASER_TASK=0,           //雷达扫描任务
+    LOCATE_TASK,            //测量任务
+    PLC_TASK,                //上传PLC任务
+    WJ_TASK,
+    UNKNOW_TASK             //未知任务单/初始化
+};
+//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
+enum Task_statu
+{
+    TASK_CREATED            =0,             //创建状态,默认值
+    TASK_SIGNED             =1,             //已签收
+    TASK_WORKING            =2,             //处理中
+    TASK_OVER               =3,             //已结束
+};
 
+//任务单基类
+class Task_Base
+{
 public:
-	//对外的接口函数,所有的任务发送方,都必须使用该函数。
-	//execute_task在内部解析了Task_Base里面的Task_type,然后转发给具体某个模块的实例对象。
-	//input:p_task_base 任务单,基类的指针,指向子类的实例,(多态)
-	Error_manager execute_task(Task_Base* p_task_base);
+    ~Task_Base();
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+    //更新任务单
+    //task_statu: 任务状态
+    //statu_information:状态说明
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+    //获取任务类型
+    Task_type   get_task_type();
+    //获取任务单状态
+    Task_statu  get_statu();
+    //获取状态说明
+    std::string get_statu_information();
+	//获取 错误码
+	Error_manager& get_task_error_manager();
+	//设置 错误码
+	void set_task_error_manager(Error_manager & error_manager);
+protected:
+    Task_Base();
+protected:
+    Task_type                   m_task_type;					//任务类型
+    Task_statu                  m_task_statu;					//任务状态
+    std::string					m_task_statu_information;		//任务状态说明
+	//错误码,任务故障信息,任务输出
+	Error_manager               m_task_error_manager;
 };
 
-
-
 #endif //TASK_COMAND_MANAGER_H
-

+ 71 - 1
task/task_command_manager.puml

@@ -2,11 +2,81 @@
 @startuml
 skinparam classAttributeIconSize 0
 
+<<<<<<< HEAD
+title  Task_Base 任务单基类
+=======
+title  binary_buf是二进制缓存
+>>>>>>> origin/hl
 
-title  task_command_manager 任务单管理类
 
 
+enum Task_type
+{
+//任务类型
+	UNKNOW_TASK             =0,				//未知任务单//初始化,默认值
+	LASER_TASK              =1,             //雷达扫描任务,
+    LOCATE_TASK             =2,             //测量任务
+    PLC_TASK                =3,             //上传PLC任务
+}
 
 
+enum Task_statu
+{
+//任务状态,如果任务故障,任务状态改为TASK_OVER,然后在m_task_error_manager 补充错误码。
+    TASK_CREATED            =0,             //创建状态,默认值
+    TASK_SIGNED             =1,             //已签收
+    TASK_WORKING            =2,             //处理中
+    TASK_OVER               =3,             //已结束
+}
 
+
+
+
+class Task_Base
+{
+//任务单基类
+==public:==
+    ~Task_Base();
+..
+    //初始化任务单,初始任务单类型为 UNKONW_TASK
+    virtual Error_manager init();
+..
+    //更新任务单
+    //task_statu: 任务状态
+    //statu_information:状态说明
+    Error_manager update_statu(Task_statu task_statu,std::string statu_information="");
+..
+    //获取任务类型
+    Task_type   get_task_type();
+..
+    //获取任务单状态
+    Task_statu  get_statu();
+..
+    //获取状态说明
+    std::string get_statu_information();
+..
+	//获取 错误码
+	Error_manager& get_task_error_manager();
+..
+	//设置 错误码
+	void set_task_error_manager(Error_manager & error_manager);
+==protected:==
+    Task_Base();
+==protected:==
+    Task_type                   m_task_type;                    //任务类型
+    Task_statu                  m_task_statu;                   //任务状态
+    std::string                 m_task_statu_information;       //任务状态说明
+	//错误码,任务故障信息,任务输出
+	Error_manager               m_task_error_manager;
+}
+
+class Error_manager
+{
+//错误码管理
+}
+Task_Base <-- Error_manager : include
+
+
+Task_Base <-- Task_type : include
+Task_Base <-- Task_statu : include
 @enduml

+ 0 - 42
tool/proto_tool.cpp

@@ -1,42 +0,0 @@
-
-
-
-#include "proto_tool.h"
-#include <fcntl.h>
-#include<unistd.h>
-#include <google/protobuf/io/zero_copy_stream_impl.h>
-#include <google/protobuf/text_format.h>
-using google::protobuf::io::FileInputStream;
-using google::protobuf::io::FileOutputStream;
-using google::protobuf::io::ZeroCopyInputStream;
-using google::protobuf::io::CodedInputStream;
-using google::protobuf::io::ZeroCopyOutputStream;
-using google::protobuf::io::CodedOutputStream;
-using google::protobuf::Message;
-
-
-//读取protobuf 配置文件,转化为protobuf参数形式
-//input:	prototxt_path :prototxt文件路径
-//ouput:	parameter: protobuf参数,这里是消息基类,实际调用时传入对应的子类即可。
-bool proto_tool::read_proto_param(std::string prototxt_path, ::google::protobuf::Message& protobuf_parameter)
-{
-	int fd = open(prototxt_path.c_str(), O_RDONLY);
-	if (fd == -1) return false;
-	FileInputStream* input = new FileInputStream(fd);
-	bool success = google::protobuf::TextFormat::Parse(input, &protobuf_parameter);
-	delete input;
-	close(fd);
-	return success;
-}
-
-
-
-
-
-
-
-
-
-
-
-

+ 0 - 56
tool/proto_tool.h

@@ -1,56 +0,0 @@
-
-
-
-
-
-#ifndef __PROTO_TOOL_H
-#define __PROTO_TOOL_H
-
-#include "../tool/singleton.h"
-#include <istream>
-#include <google/protobuf/message.h>
-
-class proto_tool:public Singleton<proto_tool>
-{
-	// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-	friend class Singleton<proto_tool>;
-public:
-	// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
-	proto_tool(const proto_tool&)=delete;
-	proto_tool& operator =(const proto_tool&)= delete;
-	~proto_tool()=default;
-private:
-	// 父类的构造函数必须保护,子类的构造函数必须私有。
-	proto_tool()=default;
-
-
-public:
-	//读取protobuf 配置文件,转化为protobuf参数形式
-	//input:	prototxt_path :prototxt文件路径
-	//ouput:	parameter: protobuf参数,这里是消息基类,实际调用时传入对应的子类即可。
-	static bool read_proto_param(std::string prototxt_path, ::google::protobuf::Message& protobuf_parameter);
-};
-
-
-
-
-#endif //__PROTO_TOOL_H
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-

+ 0 - 4
tool/singleton.cpp

@@ -1,4 +0,0 @@
-
-#include "singleton.h"
-
-

+ 0 - 81
tool/singleton.h

@@ -1,81 +0,0 @@
-
-/* Singleton 是单例类的模板。
- * https://www.cnblogs.com/sunchaothu/p/10389842.html
- * 单例 Singleton 是设计模式的一种,其特点是只提供唯一一个类的实例,具有全局变量的特点,在任何位置都可以通过接口获取到那个唯一实例;
- * 全局只有一个实例:static 特性,同时禁止用户自己声明并定义实例(把构造函数设为 private 或者 protected)
- * Singleton 模板类对这种方法进行了一层封装。
- * 单例类需要从Singleton继承。
- * 子类需要将自己作为模板参数T 传递给 Singleton<T> 模板;
- * 同时需要将基类声明为友元,这样Singleton才能调用子类的私有构造函数。
-// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-// 父类的构造函数必须保护,子类的构造函数必须私有。
-// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来操作 唯一的实例。
- * */
-
-#ifndef __SINGLIETON_H
-#define __SINGLIETON_H
-
-//#include <iostream>
-
-template<typename T>
-class Singleton
-{
-public:
-	//获取单例的引用
-	static T& get_instance_references()
-	{
-		static T instance;
-		return instance;
-	}
-	//获取单例的指针
-	static T* get_instance_pointer()
-	{
-		return &(get_instance_references());
-	}
-
-	virtual ~Singleton()
-	{
-//		std::cout<<"destructor called!"<<std::endl;
-	}
-
-	Singleton(const Singleton&)=delete;					//关闭拷贝构造函数
-	Singleton& operator =(const Singleton&)=delete;		//关闭赋值函数
-
-protected:
-	//构造函数需要是 protected,这样子类才能继承;
-	Singleton()
-	{
-//		std::cout<<"constructor called!"<<std::endl;
-	}
-
-};
-
-/*
-// 如下是 使用样例:
-// 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-// 父类的构造函数必须保护,子类的构造函数必须私有。
-// 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
-
-class DerivedSingle:public Singleton<DerivedSingle>
-{
- // 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
-	friend class Singleton<DerivedSingle>;
-public:
- // 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
-	DerivedSingle(const DerivedSingle&)=delete;
-	DerivedSingle& operator =(const DerivedSingle&)= delete;
- 	~DerivedSingle()=default;
-private:
- // 父类的构造函数必须保护,子类的构造函数必须私有。
-	DerivedSingle()=default;
-};
-
-int main(int argc, char* argv[]){
-	DerivedSingle& instance1 = DerivedSingle::get_instance_references();
-	DerivedSingle* p_instance2 = DerivedSingle::get_instance_pointer();
-	return 0;
-}
-
- */
-
-#endif

+ 1 - 1
tool/thread_condition.cpp

@@ -91,7 +91,7 @@ void Thread_condition::kill_all()
 	m_condition_variable.notify_all();
 }
 
-//判断是否存活,只有活着才能继续支持子线程从功能函数,否则需要强制退出函数并结束子线程
+//判断是否或者,return !m_kill_flag
 bool Thread_condition::is_alive()
 {
 	return !m_kill_flag;

+ 1 - 1
tool/thread_condition.h

@@ -69,7 +69,7 @@ public:
 	//		通过等待之后,也要检查kill的状态,如果为真,那么就不能执行功能函数,应该直接return
 	void kill_all();
 
-	//判断是否存活,只有活着才能继续支持子线程从功能函数,否则需要强制退出函数并结束子线程
+	//判断是否或者,return !m_kill_flag
 	bool is_alive();
 
 public: