浏览代码

velodyne测量模块完成修改,运行段错误,待debug

yct 3 年之前
父节点
当前提交
95c6064d33

+ 63 - 42
CMakeLists.txt

@@ -62,58 +62,79 @@ aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/communication COMMUNICATION_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/system SYSTEM_SRC )
 aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/verify VERIFY_SRC )
 
-# add_executable(measure_wj
-#         main.cpp
-#         ${ERROR_SRC}
-#         ${message_src}
-
-# 		${WANJI_LIDAR_SRC}
-#         ${TASK_MANAGER_SRC}
-#         ${TOOL_SRC}
-#         ${COMMUNICATION_SRC}
-#         ${SYSTEM_SRC}
-# 		${VERIFY_SRC}
-
-# 		)
-
-# target_link_libraries(measure_wj
-#         /usr/local/lib/libglog.a
-#         /usr/local/lib/libgflags.a
-#         /usr/local/lib/liblivox_sdk_static.a
-#         /usr/local/apr/lib/libapr-1.a
-#         nnxx
-#         nanomsg
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/velodyne_lidar/match3d/common VELODYNE_LIDAR_COMMON)
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/velodyne_lidar/match3d/ VELODYNE_LIDAR_MATCH)
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/velodyne_lidar/velodyne_driver VELODYNE_LIDAR_DRIVER)
+aux_source_directory(${CMAKE_CURRENT_LIST_DIR}/velodyne_lidar VELODYNE_LIDAR)
+
+add_executable(measure_wj
+        main.cpp
+        ${ERROR_SRC}
+        ${message_src}
+
+		${WANJI_LIDAR_SRC}
+        ${TASK_MANAGER_SRC}
+        ${TOOL_SRC}
+        ${COMMUNICATION_SRC}
+        ${SYSTEM_SRC}
+		${VERIFY_SRC}
+
+    ${VELODYNE_LIDAR_COMMON}
+    ${VELODYNE_LIDAR_MATCH}
+    ${VELODYNE_LIDAR_DRIVER}
+    ${VELODYNE_LIDAR}
+		)
+
+target_link_libraries(measure_wj
+        /usr/local/lib/libglog.a
+        /usr/local/lib/libgflags.a
+        /usr/local/lib/liblivox_sdk_static.a
+        /usr/local/apr/lib/libapr-1.a
+        nnxx
+        nanomsg
+
+        ${PROTOBUF_LIBRARIES}
+        ${OpenCV_LIBS}
+        ${GLOG_LIBRARIES}
+        ${PCL_LIBRARIES}
+		${CERES_LIBRARIES}
+    ${YAML_CPP_LIBRARIES}
 
-#         ${PROTOBUF_LIBRARIES}
-#         ${OpenCV_LIBS}
-#         ${GLOG_LIBRARIES}
-#         ${PCL_LIBRARIES}
-# 		${CERES_LIBRARIES}
+        -lpthread
+        )
 
-#         -lpthread
-#         )
 
-aux_source_directory(./velodyne_lidar/match3d/common VELODYNE_LIDAR_COMMON)
-aux_source_directory(./velodyne_lidar/match3d/ VELODYNE_LIDAR_MATCH)
 
 
 # vlp16 driver test
 add_executable(vlp16 tests/vlp16_driver_test.cpp 
-velodyne_lidar/velodyne_driver/input.cc 
-velodyne_lidar/velodyne_driver/rawdata.cc
-velodyne_lidar/velodyne_driver/calibration.cc
-velodyne_lidar/velodyne_driver/velodyne_lidar_device.cpp
-velodyne_lidar/velodyne_driver/velodyne_lidar_scan_task.cpp
-velodyne_lidar/velodyne_config.pb.cc
 ${ERROR_SRC}
-${TOOL_SRC}
-${TASK_MANAGER_SRC}
+${message_src}
+
 ${WANJI_LIDAR_SRC}
-velodyne_lidar/ground_region.cpp
+${TASK_MANAGER_SRC}
+${TOOL_SRC}
+${COMMUNICATION_SRC}
+${SYSTEM_SRC}
+${VERIFY_SRC}
+
 ${VELODYNE_LIDAR_COMMON}
 ${VELODYNE_LIDAR_MATCH}
+${VELODYNE_LIDAR_DRIVER}
+${VELODYNE_LIDAR}
 )
 target_link_libraries(vlp16 
-${GLOG_LIBRARIES} ${PCL_LIBRARIES} ${PROTOBUF_LIBRARIES} ${YAML_CPP_LIBRARIES} ${OpenCV_LIBS}
-        ${GLOG_LIBRARIES}
-		${CERES_LIBRARIES})
+/usr/local/lib/libglog.a
+/usr/local/lib/libgflags.a
+/usr/local/lib/liblivox_sdk_static.a
+/usr/local/apr/lib/libapr-1.a
+nnxx
+nanomsg
+
+${PROTOBUF_LIBRARIES}
+${OpenCV_LIBS}
+${GLOG_LIBRARIES}
+${PCL_LIBRARIES}
+${CERES_LIBRARIES}
+${YAML_CPP_LIBRARIES}
+)

+ 10 - 3
main.cpp

@@ -13,9 +13,10 @@
 #include "./system/system_communication.h"
 #include "./system/system_executor.h"
 
-#include "./wanji_lidar/wanji_lidar_device.h"
+// #include "./wanji_lidar/wanji_lidar_device.h"
 #include "./tool/proto_tool.h"
 #include "./wanji_lidar/wanji_manager.h"
+#include "./velodyne_lidar/velodyne_manager.h"
 
 #define LIVOX_NUMBER	     2
 
@@ -75,10 +76,14 @@ int main(int argc,char* argv[])
 	std::cout << " huli test :::: " << " t_terminal_id = " << t_terminal_id << std::endl;
 
 	// 初始化
-	Wanji_manager::get_instance_references().wanji_manager_init();
-	std::cout << "wanji_manager = " << Wanji_manager::get_instance_references().check_status().to_string() << std::endl;
+	// Wanji_manager::get_instance_references().wanji_manager_init();
+	// std::cout << "wanji_manager = " << Wanji_manager::get_instance_references().check_status().to_string() << std::endl;
+	Velodyne_manager::get_instance_references().velodyne_manager_init(t_terminal_id);
+	std::cout << "wanji_manager = " << Velodyne_manager::get_instance_references().check_status().to_string() << std::endl;
+
 	System_executor::get_instance_references().system_executor_init(4, t_terminal_id);
 	std::cout << "System_executor = " << System_executor::get_instance_references().get_system_executor_status() << std::endl;
+
 	System_communication::get_instance_references().communication_init();
 
 	// prev_test_pred_task();
@@ -93,6 +98,8 @@ int main(int argc,char* argv[])
 	// 反初始化
 	System_communication::get_instance_references().communication_uninit();
 	System_executor::get_instance_references().system_executor_uninit();
+	// Wanji_manager::get_instance_references().wanji_manager_uninit();
+	Velodyne_manager::get_instance_references().Velodyne_manager_uninit();
 
 	return 0;
 }

+ 4 - 4
setting/communication.prototxt

@@ -3,8 +3,8 @@
 communication_parameters
 {
 
-#   bind_string:"tcp://192.168.2.166:9000"
- #  connect_string_vector:"tcp://192.168.2.166:9001"
+  bind_string:"tcp://192.168.2.119:30010"
+  connect_string_vector:"tcp://192.168.2.119:30000"
  # connect_string_vector:"tcp://192.168.2.166:9002"
 
   # connect_string_vector:"tcp://192.168.2.125:9876"
@@ -24,8 +24,8 @@ communication_parameters
 
 #   connect_string_vector:"tcp://192.168.2.233:2333"
 
-bind_string:"tcp://192.168.0.64:30010"
-connect_string_vector:"tcp://192.168.0.64:30000"
+# bind_string:"tcp://192.168.0.64:30010"
+# connect_string_vector:"tcp://192.168.0.64:30000"
 
 
 }

+ 5 - 0
setting/velodyne_manager.prototxt

@@ -1,5 +1,8 @@
 fence_data_path:"/home/zx/data/fence_wj"
 #fence_log_path:"/home/zx/yct/MainStructure/new_electronic_fence/log"
+left_model_path:"/home/youchen/extra_space/chutian/measure/puai_wj_2021/setting/left_model.txt"
+right_model_path:"/home/youchen/extra_space/chutian/measure/puai_wj_2021/setting/right_model.txt"
+distribution_mode:false
 
 #1
 velodyne_lidars
@@ -8,6 +11,7 @@ velodyne_lidars
     port:2368
     model:"VLP16"
     calibrationFile:"../setting/VLP16db.yaml"
+    lidar_id:0
     max_range:5.0
     min_range:0.1
     min_angle:0
@@ -28,4 +32,5 @@ region
 	maxy:3.08
 	minz:0.01
 	maxz:0.2
+    region_id:0
 }

+ 150 - 32
system/system_executor.cpp

@@ -3,13 +3,15 @@
 //
 
 #include "system_executor.h"
+#include "../tool/common_data.h"
+#include "../tool/measure_filter.h"
 #include "../message/measure_message.pb.h"
 #include "../system/system_communication.h"
+
 #include "../wanji_lidar/wanji_manager.h"
-#include "../tool/common_data.h"
-#include "../wanji_lidar/measure_filter.h"
+#include "../velodyne_lidar/velodyne_manager.h"
 
-std::ofstream g_debug_file;
+// std::ofstream g_debug_file; // 用于测试滤波功能
 
 System_executor::System_executor()
 {
@@ -33,8 +35,8 @@ Error_manager System_executor::system_executor_init(int threads_size, int termin
 //反初始化
 Error_manager System_executor::system_executor_uninit()
 {
-    if(g_debug_file.is_open())
-        g_debug_file.close();
+    // if(g_debug_file.is_open())
+    //     g_debug_file.close();
 
 	m_thread_pool.thread_pool_uninit();
 	m_system_executor_status = SYSTEM_EXECUTOR_UNKNOW;
@@ -64,6 +66,7 @@ Error_manager System_executor::check_msg(Communication_message* p_msg)
 				{
 					// //检查终端id
 					// 普爱不检查终端id
+					// 楚天检查终端id
 					// if ( t_ground_detect_request_msg.terminal_id() == m_terminal_id )
 					// {
 						return Error_code::SUCCESS;
@@ -225,10 +228,10 @@ Error_manager System_executor::check_status()
 //定时发送状态信息
 Error_manager System_executor::encapsulate_send_status()
 {
-    if(!g_debug_file.is_open())
-    {
-        g_debug_file.open("./filter_debug_result.txt", std::ios::app);
-    }
+    // if(!g_debug_file.is_open())
+    // {
+    //     g_debug_file.open("./filter_debug_result.txt", std::ios::app);
+    // }
 
 	Error_manager t_error;
 	//创建一条状态消息
@@ -238,11 +241,73 @@ Error_manager System_executor::encapsulate_send_status()
 	t_ground_status_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
 	t_ground_status_msg.mutable_base_info()->set_receiver(message::Communicator::eEmpty);
 
-    // 普爱统一一个万集节点, 各终端消息分别发送
 	t_ground_status_msg.set_terminal_id(m_terminal_id);
 
+	// 创建各区域状态消息, 公共消息名字依旧包含wj,不做修改
+	// manager
+	Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
+	t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
+
+	// lidar
+	std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
+	std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
+	for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
+	{
+		t_velodyne_lidar_status_map.emplace(std::pair<int, Velodyne_lidar_device::Velodyne_lidar_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
+	}
+
+	// region
+	std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
+	int region_index = 0;
+	for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
+	{
+		// 以t_ground_status_msg为模板创建各区域心跳消息
+		message::Ground_status_msg t_multi_status_msg;
+		t_multi_status_msg.CopyFrom(t_ground_status_msg);
+        t_multi_status_msg.set_terminal_id(iter->second->get_terminal_id());
+		t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
+		velodyne::Region t_param = iter->second->get_param();
+		for (size_t j = 0; j <t_param.lidar_ids_size(); j++)
+		{
+			std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status>::iterator t_status_iter = t_velodyne_lidar_status_map.find(t_param.lidar_ids(j));
+			if(t_status_iter== t_velodyne_lidar_status_map.end())
+			{
+				LOG(WARNING) << "lidar status cannot be found, param error";
+			}else{
+				t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
+			}
+		}
+		//velodyne雷达的自动定位信息
+		Common_data::Car_wheel_information	t_car_wheel_information;
+		t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
+
+		//无论定位结果如何, 都要填充数据, 即使全部写0, 必须保证通信格式正确.
+		message::Locate_information t_locate_information;
+		//= t_multi_status_msg.add_locate_information_realtime();
+		t_locate_information.set_locate_x(t_car_wheel_information.center_x);
+		t_locate_information.set_locate_y(t_car_wheel_information.center_y);
+		t_locate_information.set_locate_angle(t_car_wheel_information.car_angle);
+		t_locate_information.set_locate_length(0);
+		t_locate_information.set_locate_width(0);
+		t_locate_information.set_locate_height(0);
+		t_locate_information.set_locate_wheel_base(t_car_wheel_information.wheel_base);
+		t_locate_information.set_locate_wheel_width(t_car_wheel_information.wheel_width);
+		t_locate_information.set_locate_front_theta(t_car_wheel_information.front_theta);
+		t_locate_information.set_locate_correct(t_car_wheel_information.correctness);
+		t_multi_status_msg.mutable_locate_information_realtime()->CopyFrom(t_locate_information);
+		t_multi_status_msg.set_ground_status(t_car_wheel_information.correctness?message::Ground_statu::Car_correct:message::Ground_statu::Noise);
+
+		t_multi_status_msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
+        t_multi_status_msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
+        t_multi_status_msg.mutable_error_manager()->set_error_description(t_error.get_error_description(), t_error.get_description_length());
+        std::string t_msg = t_multi_status_msg.SerializeAsString();
+        System_communication::get_instance_references().encapsulate_msg(t_msg);
+	}
+
+	// 普爱统一一个万集节点, 各终端消息分别发送
+	// 此处将t_ground_status_msg当做模板创建各区域的心跳消息. 
 	//万集716
-	Wanji_manager::Wanji_manager_status t_wanji_manager_status = Wanji_manager::get_instance_references().get_status();
+/*Wanji_manager::Wanji_manager_status t_wanji_manager_status = Wanji_manager::get_instance_references().get_status();
 	t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_wanji_manager_status);
 
 	std::map<int, Wanji_lidar_device*> & t_wanji_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
@@ -281,6 +346,7 @@ Error_manager System_executor::encapsulate_send_status()
 		t_locate_information.set_locate_front_theta(t_car_wheel_information.front_theta);
 		t_locate_information.set_locate_correct(t_car_wheel_information.correctness);
 		t_multi_status_msg.mutable_locate_information_realtime()->CopyFrom(t_locate_information);
+		t_multi_status_msg.set_ground_status(t_car_wheel_information.correctness?message::Ground_statu::Car_correct:message::Ground_statu::Noise);
 
 		t_multi_status_msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
         t_multi_status_msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
@@ -317,7 +383,10 @@ Error_manager System_executor::encapsulate_send_status()
 //            }
 ////            LOG(WARNING) << t_multi_status_msg.DebugString();
 //        }
-	}
+}*/
+
+
+
 
 //	std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = "  << std::endl;
 //	std::cout << t_ground_status_msg.DebugString() << std::endl;
@@ -370,29 +439,65 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 
 
 	//第2步, 创建万集管理模块的任务单, 并发送到 wanji_manager
-	Wanji_manager_task  t_wanji_manager_task ;
-	Common_data::Car_wheel_information	t_car_information_by_wanji;
-	t_wanji_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(3000),
+	// Wanji_manager_task  t_wanji_manager_task ;
+	// Common_data::Car_wheel_information	t_car_information_by_wanji;
+	// t_wanji_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(3000),
+	// 							   terminal_id, receive_time);
+	// t_error = Task_command_manager::get_instance_references().execute_task(&t_wanji_manager_task);
+	// 或者创建velodyne管理模块任务单,并发送到velodyne_manager
+	Velodyne_manager_task t_velodyne_manager_task;
+	Common_data::Car_wheel_information	t_car_information_by_velodyne;
+	t_velodyne_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(3000),
 								   terminal_id, receive_time);
-	t_error = Task_command_manager::get_instance_references().execute_task(&t_wanji_manager_task);
+	t_error = Task_command_manager::get_instance_references().execute_task(&t_velodyne_manager_task);							   
 
 	//第3步, 等待任务单完成
 	if ( t_error != Error_code::SUCCESS )
 	{
-		LOG(INFO) << " Wanji_manager  execute_task   error "<< this;
+		LOG(INFO) << " Wanji_manager/Velodyne_manager  execute_task   error "<< this;
 	}
 	else
 	{
+		// //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
+		// while ( t_wanji_manager_task.is_task_end() == false)
+		// {
+		// 	if ( t_wanji_manager_task.is_over_time() )
+		// 	{
+		// 		//超时处理。取消任务。
+		// 		Wanji_manager::get_instance_pointer()->cancel_task(&t_wanji_manager_task);
+		// 		t_error.error_manager_reset(Error_code::WJ_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
+		// 									" t_wanji_manager_task is_over_time ");
+		// 		t_wanji_manager_task.set_task_error_manager(t_error);
+		// 	}
+		// 	else
+		// 	{
+		// 		//继续等待
+		// 		std::this_thread::sleep_for(std::chrono::microseconds(1));
+		// 		std::this_thread::yield();
+		// 	}
+		// }
+
+		// //提取任务单 的错误码
+		// t_error = t_wanji_manager_task.get_task_error_manager();
+		// if ( t_error == Error_code::SUCCESS )
+		// {
+		// 	t_car_information_by_wanji = t_wanji_manager_task.get_car_wheel_information();
+		// }
+		// else
+		// {
+		//     LOG(INFO) << " wanji_manager_task error :::::::"  << t_wanji_manager_task.get_task_error_manager().to_string() << this;
+		// }
+		// ------------------- 切换为velodyne ------------------
 		//判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
-		while ( t_wanji_manager_task.is_task_end() == false)
+		while ( t_velodyne_manager_task.is_task_end() == false)
 		{
-			if ( t_wanji_manager_task.is_over_time() )
+			if ( t_velodyne_manager_task.is_over_time() )
 			{
 				//超时处理。取消任务。
-				Wanji_manager::get_instance_pointer()->cancel_task(&t_wanji_manager_task);
+				Wanji_manager::get_instance_pointer()->cancel_task(&t_velodyne_manager_task);
 				t_error.error_manager_reset(Error_code::WJ_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
-											" t_wanji_manager_task is_over_time ");
-				t_wanji_manager_task.set_task_error_manager(t_error);
+											" t_velodyne_manager_task is_over_time ");
+				t_velodyne_manager_task.set_task_error_manager(t_error);
 			}
 			else
 			{
@@ -403,14 +508,14 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 		}
 
 		//提取任务单 的错误码
-		t_error = t_wanji_manager_task.get_task_error_manager();
+		t_error = t_velodyne_manager_task.get_task_error_manager();
 		if ( t_error == Error_code::SUCCESS )
 		{
-			t_car_information_by_wanji = t_wanji_manager_task.get_car_wheel_information();
+			t_car_information_by_velodyne = t_velodyne_manager_task.get_car_wheel_information();
 		}
 		else
 		{
-		    LOG(INFO) << " wanji_manager_task error :::::::"  << t_wanji_manager_task.get_task_error_manager().to_string() << this;
+		    LOG(INFO) << " wanji_manager_task error :::::::"  << t_velodyne_manager_task.get_task_error_manager().to_string() << this;
 		}
 	}
 	t_result.compare_and_cover_error(t_error);
@@ -419,16 +524,29 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 	Common_data::Car_measure_information	t_car_information_result;
 
 	//第4步, 生成反馈消息
-	if(t_car_information_by_wanji.correctness == true )
+	// if(t_car_information_by_wanji.correctness == true )
+	// {
+	// 	t_car_information_result.center_x = t_car_information_by_wanji.center_x;
+	// 	t_car_information_result.center_y = t_car_information_by_wanji.center_y;
+
+	// 	t_car_information_result.car_angle = t_car_information_by_wanji.car_angle;
+	// 	t_car_information_result.wheel_base = t_car_information_by_wanji.wheel_base;
+
+	// 	t_car_information_result.wheel_width = t_car_information_by_wanji.wheel_width;
+	// 	t_car_information_result.correctness = true;
+	// }else{
+	// 	t_result.set_error_level_down(NEGLIGIBLE_ERROR);
+	// }
+	// ------------------- 切换为velodyne ------------------
+	if(t_car_information_by_velodyne.correctness == true )
 	{
-		t_car_information_result.center_x = t_car_information_by_wanji.center_x;
-		t_car_information_result.center_y = t_car_information_by_wanji.center_y;
+		t_car_information_result.center_x = t_car_information_by_velodyne.center_x;
+		t_car_information_result.center_y = t_car_information_by_velodyne.center_y;
 
-		t_car_information_result.car_angle = t_car_information_by_wanji.car_angle;
-		t_car_information_result.wheel_base = t_car_information_by_wanji.wheel_base;
-		t_car_information_result.wheel_base = t_car_information_result.wheel_base > 3000 ? 3000 : t_car_information_result.wheel_base;
+		t_car_information_result.car_angle = t_car_information_by_velodyne.car_angle;
+		t_car_information_result.wheel_base = t_car_information_by_velodyne.wheel_base;
 
-		t_car_information_result.wheel_width = t_car_information_by_wanji.wheel_width;
+		t_car_information_result.wheel_width = t_car_information_by_velodyne.wheel_width;
 		t_car_information_result.correctness = true;
 	}else{
 		t_result.set_error_level_down(NEGLIGIBLE_ERROR);

+ 11 - 0
task/task_command_manager.cpp

@@ -3,6 +3,7 @@
 
 #include "task_command_manager.h"
 #include "../wanji_lidar/wanji_manager.h"
+#include "../velodyne_lidar/velodyne_manager.h"
 //对外的接口函数,所有的任务发送方,都必须使用该函数。
 //execute_task在内部解析了Task_Base里面的Task_type,然后转发给具体某个模块的实例对象。
 //input:p_task_base 任务单,基类的指针,指向子类的实例,(多态)
@@ -60,6 +61,16 @@ Error_manager Task_command_manager::execute_task(Task_Base* p_task_base)
 				t_error = Wanji_manager::get_instance_references().execute_task(p_task_base);
 			}
 			break;
+		case VELODYNE_MANAGER_TASK:
+			if ( tp_tast_receiver != NULL )
+			{
+				t_error = ((Velodyne_manager*)tp_tast_receiver)->execute_task(p_task_base);
+			}
+			else
+			{
+				t_error = Velodyne_manager::get_instance_references().execute_task(p_task_base);
+			}
+			break;
 	    default:
 			t_error.error_manager_reset(Error_code::TASK_TYPE_IS_UNKNOW, Error_level::MINOR_ERROR,
 										" p_task_base->get_task_type() is  UNKNOW_TASK ");

+ 4 - 3
tests/vlp16_driver_test.cpp

@@ -2,7 +2,7 @@
  * @Description: vlp16驱动测试
  * @Author: yct
  * @Date: 2021-07-26 14:11:26
- * @LastEditTime: 2021-07-29 18:46:48
+ * @LastEditTime: 2021-07-30 16:25:35
  * @LastEditors: yct
  */
 
@@ -109,7 +109,7 @@ void device_test()
 }
 
 #include "../velodyne_lidar/ground_region.h"
-#include "../wanji_lidar/measure_filter.h"
+#include "../tool/measure_filter.h"
 #include "../tool/point_tool.h"
 void region_detect()
 {
@@ -155,6 +155,7 @@ void region_detect()
         param.set_maxy(3.08);
         param.set_minz(0.01);
         param.set_maxz(0.2);
+        param.set_region_id(0);
         pcl::PointCloud<pcl::PointXYZ>::Ptr left = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
         pcl::PointCloud<pcl::PointXYZ>::Ptr right = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
         if (!read_pointcloud("/home/youchen/extra_space/chutian/measure/puai_wj_2021/setting/left_model.txt", left) || !read_pointcloud("/home/youchen/extra_space/chutian/measure/puai_wj_2021/setting/right_model.txt", right))
@@ -164,7 +165,7 @@ void region_detect()
         }
         Ground_region t_region;
         std::cout << "before init" << std::endl;
-        t_region.init(0, param, left, right);
+        t_region.init(param, left, right);
         std::cout << "after init" << std::endl;
         // 测试region功能
         detect_wheel_ceres3d::Detect_result t_result;

+ 3 - 2
tool/common_data.h

@@ -14,7 +14,8 @@ class Common_data
 public:
 	//万集雷达扫描周期66ms, (频率15hz), 一般设置大一些
 #define WANJI_716_SCAN_CYCLE_MS 		75
-
+	//vlp16雷达扫描周期100ms, (频率10hz), 一般设置大一些
+#define VLP16_SCAN_CYCLE_MS 		110
 
 	//整车的测量信息
 	struct Car_measure_information
@@ -108,7 +109,7 @@ public:
 	struct Car_wheel_information_stamped
 	{
 		Car_wheel_information wheel_data;
-		std::chrono::steady_clock::time_point measure_time;
+		std::chrono::system_clock::time_point measure_time;
 				public:
 		Car_wheel_information_stamped& operator+=(const Car_wheel_information_stamped& other)
 		{

+ 2 - 2
wanji_lidar/measure_filter.h

@@ -2,7 +2,7 @@
  * @Description: 测量结果滤波器
  * @Author: yct
  * @Date: 2021-03-15 14:41:46
- * @LastEditTime: 2021-07-29 18:50:45
+ * @LastEditTime: 2021-07-30 10:33:47
  * @LastEditors: yct
  */
 
@@ -50,7 +50,7 @@ public:
         { 
             m_measure_results_map[terminal_id].push_back(data);
             // 剔除超时数据
-            while(std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::steady_clock::now()-m_measure_results_map[terminal_id].front().measure_time).count() > MAX_TIME_INTERVAL_MILLI)
+            while(std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now()-m_measure_results_map[terminal_id].front().measure_time).count() > MAX_TIME_INTERVAL_MILLI)
             {
                 m_measure_results_map[terminal_id].pop_front();
             }

+ 47 - 6
velodyne_lidar/ground_region.cpp

@@ -11,7 +11,7 @@
 #include <fcntl.h>
 
 // 测量结果滤波,不影响现有结构
-#include "../wanji_lidar/measure_filter.h"
+#include "../tool/measure_filter.h"
 
 //欧式聚类*******************************************************
 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
@@ -294,9 +294,8 @@ Ground_region::~Ground_region()
     }
 }
 
-Error_manager Ground_region::init(int terminal_id, velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
+Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
 {
-    m_terminal_id = terminal_id;
     m_region = region;
     m_detector = new detect_wheel_ceres3d(left_model,right_model);
     mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
@@ -402,11 +401,53 @@ Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, d
     return SUCCESS;
 }
 
+//外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
+Error_manager Ground_region::get_current_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
+{
+    if ( p_car_wheel_information == NULL )
+	{
+	    return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+	    					"  POINTER IS NULL ");
+	}
+	//获取指令时间之后的信息, 如果没有就会报错, 不会等待
+	if( m_detect_update_time > command_time )
+	{
+		*p_car_wheel_information = m_car_wheel_information;
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
+							 " Ground_region::get_current_wheel_information error ");
+	}
+}
+
+//外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
+Error_manager Ground_region::get_last_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
+{
+    if ( p_car_wheel_information == NULL )
+	{
+	    return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+	    					"  POINTER IS NULL ");
+	}
+	//获取指令时间之后的信息, 如果没有就会报错, 不会等待
+	if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
+	{
+		*p_car_wheel_information = m_car_wheel_information;
+		return Error_code::SUCCESS;
+	}
+	else
+	{
+		return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
+							 " Ground_region::get_current_wheel_information error ");
+	}
+}
+
 Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
 {
     std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
     mp_cloud_collection = cloud;
-    m_cloud_collection_time = std::chrono::steady_clock::now();
+    m_cloud_collection_time = std::chrono::system_clock::now();
     m_measure_condition.notify_one(false, true);
     return SUCCESS;
 }
@@ -421,7 +462,7 @@ void Ground_region::thread_measure_func()
             m_region_status = E_BUSY;
             detect_wheel_ceres3d::Detect_result t_result;
             Error_manager ec = detect(mp_cloud_collection, t_result);
-            m_detect_update_time = std::chrono::steady_clock::now();
+            m_detect_update_time = std::chrono::system_clock::now();
             m_car_wheel_information.center_x = t_result.cx;
             m_car_wheel_information.center_y = t_result.cy;
             m_car_wheel_information.car_angle = t_result.theta;
@@ -434,7 +475,7 @@ void Ground_region::thread_measure_func()
                 Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
 				t_wheel_info_stamped.wheel_data = m_car_wheel_information;
 				t_wheel_info_stamped.measure_time = m_detect_update_time;
-				Measure_filter::get_instance_references().update_data(m_terminal_id, t_wheel_info_stamped);
+				Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
             }
             else
             {

+ 16 - 5
velodyne_lidar/ground_region.h

@@ -32,25 +32,37 @@ public:
 
 		E_FAULT = 10, //故障
 	};
+   #define GROUND_REGION_DETECT_CYCLE_MS 200
 
    Ground_region();
    ~Ground_region();
    // 区域类初始化
-   Error_manager init(int terminal_id, velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model);
+   Error_manager init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model);
    // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果
    Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &result);
    // 公有点云更新函数,传入最新点云获得结果
    Error_manager update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
+   //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
+	Error_manager get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
+												std::chrono::system_clock::time_point command_time);
+   //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
+	Error_manager get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
+											 std::chrono::system_clock::time_point command_time);
+
    // 获取区域终端号, 注意!未初始化调用将返回-1
    int get_terminal_id()
    {
       if(m_region_status == E_UNKNOWN)
          return -1;
       else
-         return m_terminal_id;
+         return m_region.region_id();
    }
    // 获取区域状态
    Ground_region_status get_status() { return m_region_status; }
+   // 获取更新时间
+   std::chrono::system_clock::time_point get_detect_update_time() { return m_detect_update_time; }
+   // 获取配置参数
+   velodyne::Region get_param() { return m_region; }
 
 private:
    // 点云分类,z切,3d优化
@@ -67,7 +79,6 @@ private:
 
 
 private:
-   int m_terminal_id; // 当前区域对应id
    velodyne::Region m_region; // 区域配置
    detect_wheel_ceres3d *m_detector; // 检测器
    Ground_region_status m_region_status; // 区域状态
@@ -78,10 +89,10 @@ private:
 
    std::mutex	 								      m_cloud_collection_mutex;       // 点云更新互斥锁, 内存由上级管理
 	pcl::PointCloud<pcl::PointXYZ>::Ptr 		mp_cloud_collection;			//扫描点的点云集合, 内存由上级管理
-   std::chrono::steady_clock::time_point     m_cloud_collection_time; // 点云更新时间
+   std::chrono::system_clock::time_point     m_cloud_collection_time; // 点云更新时间
 
    Common_data::Car_wheel_information			m_car_wheel_information;		//车轮的定位结果,
-	std::chrono::steady_clock::time_point		m_detect_update_time;			//定位结果的更新时间.
+	std::chrono::system_clock::time_point		m_detect_update_time;			//定位结果的更新时间.
 };
 
 #endif //LIDARMEASURE__GROUD_REGION_HPP_

+ 3 - 3
velodyne_lidar/match3d/detect_wheel_ceres3d.h

@@ -2,8 +2,8 @@
 // Created by zx on 2020/7/1.
 //
 
-#ifndef CERES_TEST_DETECT_WHEEL_CERES_H
-#define CERES_TEST_DETECT_WHEEL_CERES_H
+#ifndef DETECT_WHEEL_CERES_3D_H
+#define DETECT_WHEEL_CERES_3D_H
 
 #include <ceres/ceres.h>
 #include <glog/logging.h>
@@ -92,4 +92,4 @@ public:
 };
 
 
-#endif //CERES_TEST_DETECT_WHEEL_CERES_H
+#endif //DETECT_WHEEL_CERES_3D_H

文件差异内容过多而无法显示
+ 751 - 450
velodyne_lidar/velodyne_config.pb.cc


文件差异内容过多而无法显示
+ 680 - 373
velodyne_lidar/velodyne_config.pb.h


+ 12 - 6
velodyne_lidar/velodyne_config.proto

@@ -7,6 +7,9 @@ message velodyneManagerParams
     repeated Region region=2;
     optional string fence_data_path=3 [default=""];
     optional string fence_log_path=4 [default=""];
+    optional string left_model_path=5 [default=""];
+    optional string right_model_path=6 [default=""];
+    required bool distribution_mode=7 [default=false];//是否分布式模式,分布式模式下,各程序仅启动与自身区域相关模块
 }
 
 message velodyneLidarParams
@@ -15,12 +18,13 @@ message velodyneLidarParams
     required int32 port=2[default=2368];
     required string model=3[default="VLP16"];
     required string calibrationFile=4[default=""];
-    optional float max_range=5[default=10.0];
-    optional float min_range=6[default=0.15];
-    optional int32 min_angle=7[default=0];
-    optional int32 max_angle=8[default=360];
-    optional int32 rpm=9[default=600];
-    optional Calib_parameter calib=10;
+    required int32 lidar_id=5[default=0];
+    optional float max_range=6[default=10.0];
+    optional float min_range=7[default=0.15];
+    optional int32 min_angle=8[default=0];
+    optional int32 max_angle=9[default=360];
+    optional int32 rpm=10[default=600];
+    optional Calib_parameter calib=11;
 }
 
 message Calib_parameter
@@ -41,4 +45,6 @@ message Region
     required float maxy=4;
     required float minz=5;
     required float maxz=6;
+    required int32 region_id=7;
+    repeated int32 lidar_ids=8;
 }

+ 4 - 2
velodyne_lidar/velodyne_driver/velodyne_lidar_device.cpp

@@ -74,6 +74,7 @@ void Velodyne_lidar_device::dev_info_config(std::string model, int rpm)
 // 初始化
 Error_manager Velodyne_lidar_device::init(velodyne::velodyneLidarParams params)
 {
+	m_params = params;
 	Error_manager t_error;
 	LOG(INFO) << " Velodyne_lidar_device::init " << this;
 	m_num_packet_inside = 0;
@@ -81,6 +82,7 @@ Error_manager Velodyne_lidar_device::init(velodyne::velodyneLidarParams params)
 	m_velodyne_lidar_device_status = E_UNKNOWN;
 	m_velodyne_socket_status = E_UNKNOWN;
 	m_velodyne_protocol_status = E_UNKNOWN;
+	m_lidar_id = params.lidar_id();
 
 	// 设置雷达内参矩阵
 	Eigen::AngleAxisd rot_x = Eigen::AngleAxisd(params.calib().r(), Eigen::Vector3d::UnitX());
@@ -415,7 +417,7 @@ Error_manager Velodyne_lidar_device::get_last_cloud(std::mutex *p_mutex, pcl::Po
 		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
 							 "  POINTER IS NULL ");
 	}
-	if (m_parse_ring_time > command_time)
+	if (m_parse_ring_time > command_time - std::chrono::milliseconds(m_params.rpm()/60))
 	{
 		std::unique_lock<std::mutex> lck(*p_mutex);
 		{
@@ -446,7 +448,7 @@ Error_manager Velodyne_lidar_device::get_last_cloud(pcl::PointCloud<pcl::PointXY
 		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
 							 "  POINTER IS NULL ");
 	}
-	if (m_parse_ring_time > command_time)
+	if (m_parse_ring_time > command_time - std::chrono::milliseconds(m_params.rpm()/60))
 	{
 		std::lock_guard<std::mutex> lck(m_cloud_mutex);
 		if (m_ring_cloud.size() <= 0)

+ 6 - 0
velodyne_lidar/velodyne_driver/velodyne_lidar_device.h

@@ -53,6 +53,8 @@ public:
 	//判断是否为待机,如果已经准备好,则可以执行任务。
 	bool is_ready();
 
+	int get_lidar_id() { return m_lidar_id; }
+
 	//外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
 	Error_manager get_new_cloud_and_wait(std::mutex* p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
 							std::chrono::steady_clock::time_point command_time, int timeout_ms=1500);
@@ -92,6 +94,10 @@ protected:
 	Velodyne_lidar_device_status m_velodyne_lidar_device_status;	//万集设备状态
 	Velodyne_lidar_device_status m_velodyne_socket_status;
 	Velodyne_lidar_device_status m_velodyne_protocol_status;
+	// 雷达编号
+	int m_lidar_id;
+	// 雷达配置
+	velodyne::velodyneLidarParams m_params;
 
 	//子模块
 	velodyne_driver::InputSocket m_input_socket;					   //负责雷达通信, 接受雷达数据

+ 366 - 41
velodyne_lidar/velodyne_manager.cpp

@@ -2,20 +2,20 @@
  * @Description: 
  * @Author: yct
  * @Date: 2021-07-23 16:39:04
- * @LastEditTime: 2021-07-28 16:29:13
+ * @LastEditTime: 2021-07-30 17:25:21
  * @LastEditors: yct
  */
 #include "velodyne_manager.h"
 #include "../tool/proto_tool.h"
 
 //初始化 雷达 管理模块。如下三选一
-Error_manager Velodyne_manager::velodyne_manager_init()
+Error_manager Velodyne_manager::velodyne_manager_init(int terminal)
 {
-    return velodyne_manager_init_from_protobuf(VELODYNE_MANAGER_PARAMETER_PATH);
+    return velodyne_manager_init_from_protobuf(VELODYNE_MANAGER_PARAMETER_PATH, terminal);
 }
 
 //初始化 雷达 管理模块。从文件读取
-Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(std::string prototxt_path)
+Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(std::string prototxt_path,int terminal)
 {
     velodyne::velodyneManagerParams t_velo_params;
     if (!proto_tool::read_proto_param(prototxt_path, t_velo_params))
@@ -23,66 +23,90 @@ Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(std::string
         return Error_manager(WJ_MANAGER_READ_PROTOBUF_ERROR, MINOR_ERROR, "velodyne_manager read_proto_param  failed");
     }
 
-    return velodyne_manager_init_from_protobuf(t_velo_params);
+    return velodyne_manager_init_from_protobuf(t_velo_params, terminal);
 }
 
 //初始化 雷达 管理模块。从protobuf读取
-Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::velodyneManagerParams & velodyne_parameters)
+Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::velodyneManagerParams & velodyne_parameters,int terminal)
 {
     LOG(INFO) << " ---velodyne_manager_init_from_protobuf run--- "<< this;
 	Error_manager t_error;
 	if ( m_velodyne_manager_status != E_UNKNOWN)
 	{
-		return Error_manager(Error_code::WJ_MANAGER_INIT_ERROR, Error_level::MINOR_ERROR,
+		return Error_manager(Error_code::VELODYNE_MANAGER_INIT_ERROR, Error_level::MINOR_ERROR,
 							 " velodyne_manager::velodyne_manager_init_from_protobuf init repeat error ");
 	}
+	m_terminal_id = terminal;
 
-	//创建雷达设备
-	int t_velodyne_lidar_size = velodyne_parameters.velodyne_lidars_size();
-	for(int i=0;i<t_velodyne_lidar_size;++i)
+	// 判断参数合法性
+	if(!velodyne_parameters.has_left_model_path() || ! velodyne_parameters.has_right_model_path())
 	{
-		Velodyne_lidar_device* p_velodyne_lidar_device(new Velodyne_lidar_device);
-		t_error = p_velodyne_lidar_device->init(velodyne_parameters.velodyne_lidars(i));
-//		LOG(WARNING) << wanji_parameters.wj_lidar(i).DebugString();
-		if ( t_error != Error_code::SUCCESS )
-		{
-			delete(p_velodyne_lidar_device);
-			return t_error;
-		}
-		m_velodyne_lidar_device_map[i] = (p_velodyne_lidar_device);
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+							 " velodyne_manager::velodyne_manager_init_from_protobuf param must contain model path");
+	}
+	pcl::PointCloud<pcl::PointXYZ>::Ptr left = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
+	pcl::PointCloud<pcl::PointXYZ>::Ptr right = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
+	if (!read_pointcloud(velodyne_parameters.left_model_path(), left) || !read_pointcloud(velodyne_parameters.right_model_path(), right))
+	{
+		LOG(ERROR) << "cannot read left/right model ";
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MAJOR_ERROR,
+							 " velodyne_manager::velodyne_manager_init_from_protobuf left/right model path error");
 	}
 
+	// 根据是否处于分布式模式,决定初始化设备数量
 	//创建预测算法
-	int t_ground_region_size = velodyne_parameters.region_size;
-	for(int i=0;i<t_ground_region_size;++i)
-	{
-		Region_worker* p_region_worker(new Region_worker);
-		Point2D_tool::Point2D_box t_point2d_box;
-		t_point2d_box.x_min = wanji_parameters.regions(i).minx();
-		t_point2d_box.x_max = wanji_parameters.regions(i).maxx();
-		t_point2d_box.y_min = wanji_parameters.regions(i).miny();
-		t_point2d_box.y_max = wanji_parameters.regions(i).maxy();
-		// changed by yct, 传入终端index,仅普爱使用
-		t_error = p_region_worker->init(t_point2d_box, &m_cloud_collection_mutex, mp_cloud_collection, i);
-		if ( t_error != Error_code::SUCCESS )
+	std::set<int> lidar_selection_set;
+	for (int i = 0; i < velodyne_parameters.region_size(); ++i)
+	{
+		// 非分布式则创建所有区域,否则只创建对应区域
+		if (!velodyne_parameters.distribution_mode() || (velodyne_parameters.distribution_mode() && velodyne_parameters.region(i).region_id() == m_terminal_id))
 		{
-			delete(p_region_worker);
-			return t_error;
+			// 分布式模式记录待创建雷达编号
+			if(velodyne_parameters.distribution_mode())
+			{
+				for (size_t j = 0; j < velodyne_parameters.region(i).lidar_ids_size(); j++)
+				{
+					lidar_selection_set.emplace(velodyne_parameters.region(i).lidar_ids(j));
+				}
+			}
+
+			Ground_region *p_ground_region(new Ground_region);
+			t_error = p_ground_region->init(velodyne_parameters.region(i), left, right);
+			if (t_error != Error_code::SUCCESS)
+			{
+				delete (p_ground_region);
+				return t_error;
+			}
+			m_ground_region_map[velodyne_parameters.region(i).region_id()] = p_ground_region;
+		}
+	}
+	
+	//创建雷达设备
+	for(int i=0;i<velodyne_parameters.velodyne_lidars_size();++i)
+	{
+		// 非分布式模式创建所有雷达,否则只创建对应区域标记的雷达
+		if (!velodyne_parameters.distribution_mode() || (velodyne_parameters.distribution_mode() && lidar_selection_set.find(velodyne_parameters.velodyne_lidars(i).lidar_id()) != lidar_selection_set.end() ))
+		{
+			Velodyne_lidar_device *p_velodyne_lidar_device(new Velodyne_lidar_device);
+			t_error = p_velodyne_lidar_device->init(velodyne_parameters.velodyne_lidars(i));
+			if (t_error != Error_code::SUCCESS)
+			{
+				delete (p_velodyne_lidar_device);
+				return t_error;
+			}
+			m_velodyne_lidar_device_map[velodyne_parameters.velodyne_lidars(i).lidar_id()] = p_velodyne_lidar_device;
 		}
-		m_region_worker_map[i] = p_region_worker;
 	}
-
-
 
 	//启动 收集点云的线程。默认 。
 	m_collect_cloud_condition.reset(false, false, false);
-	mp_collect_cloud_thread = new std::thread(&Wanji_manager::collect_cloud_thread_fun, this);
+	mp_collect_cloud_thread = new std::thread(&Velodyne_manager::collect_cloud_thread_fun, this);
 
 	//启动 执行的线程。默认 。
 	m_execute_condition.reset(false, false, false);
-	mp_execute_thread = new std::thread(&Wanji_manager::execute_thread_fun, this);
+	mp_execute_thread = new std::thread(&Velodyne_manager::execute_thread_fun, this);
 
-	m_wanji_manager_status = E_READY;
+	m_velodyne_manager_status = E_READY;
 
 	return Error_code::SUCCESS;
 }
@@ -90,5 +114,306 @@ Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::ve
 // 反初始化
 Error_manager Velodyne_manager::Velodyne_manager_uninit()
 {
-    
-}
+    LOG(INFO) << " ---velodyne_manager_uninit run--- "<< this;
+	//关闭线程
+	if (mp_collect_cloud_thread)
+	{
+		m_collect_cloud_condition.kill_all();
+	}
+	if (mp_execute_thread)
+	{
+		m_execute_condition.kill_all();
+	}
+	//回收线程的资源
+	if (mp_collect_cloud_thread)
+	{
+		mp_collect_cloud_thread->join();
+		delete mp_collect_cloud_thread;
+		mp_collect_cloud_thread = NULL;
+	}
+	if (mp_execute_thread)
+	{
+		mp_execute_thread->join();
+		delete mp_execute_thread;
+		mp_execute_thread = NULL;
+	}
+	//回收雷达设备
+	for (auto iter = m_velodyne_lidar_device_map.begin(); iter != m_velodyne_lidar_device_map.end(); ++iter)
+	{
+		delete(iter->second);
+	}
+	m_velodyne_lidar_device_map.clear();
+
+	for (auto iter = m_ground_region_map.begin(); iter != m_ground_region_map.end(); ++iter)
+	{
+		delete(iter->second);
+	}
+	m_ground_region_map.clear();
+
+	m_velodyne_manager_status = E_UNKNOWN;
+
+	return Error_code::SUCCESS;
+}
+
+//对外的接口函数,负责接受并处理任务单,
+Error_manager Velodyne_manager::execute_task(Task_Base* p_velodyne_manager_task)
+{
+	LOG(INFO) << " ---Velodyne_manager::execute_task run---  " << this;
+	Error_manager t_error;
+	Error_manager t_result;
+
+	//检查指针
+	if (p_velodyne_manager_task == NULL)
+	{
+		return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
+							 "Velodyne_manager::execute_task failed, POINTER_IS_NULL");
+	}
+	//检查任务类型,
+	if (p_velodyne_manager_task->get_task_type() != VELODYNE_MANAGER_TASK)
+	{
+		return Error_manager(Error_code::VELODYNE_MANAGER_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
+							 "laser task type error != WANJI_MANAGER_TASK ");
+	}
+
+	//检查接收方的状态
+	t_error = check_status();
+	if (t_error != SUCCESS)
+	{
+		t_result.compare_and_cover_error(t_error);
+	}
+	else
+	{
+		//接受任务,并将任务的状态改为TASK_SIGNED已签收
+		mp_velodyne_manager_task = (Velodyne_manager_task *)p_velodyne_manager_task;
+		mp_velodyne_manager_task->set_task_statu(TASK_SIGNED);
+
+		//启动雷达管理模块,的核心工作线程
+		m_velodyne_manager_status = E_BUSY;
+		m_execute_condition.notify_all(true);
+
+		//将任务的状态改为 TASK_WORKING 处理中
+		mp_velodyne_manager_task->set_task_statu(TASK_WORKING);
+
+		//return 之前要填充任务单里面的错误码.
+		if (t_result != Error_code::SUCCESS)
+		{
+			//忽略轻微故障
+			if (t_result.get_error_level() >= Error_level::MINOR_ERROR)
+			{
+				//将任务的状态改为 TASK_ERROR 结束错误
+				mp_velodyne_manager_task->set_task_statu(TASK_ERROR);
+			}
+			//返回错误码
+			mp_velodyne_manager_task->compare_and_cover_task_error_manager(t_result);
+		}
+	}
+
+	return t_result;
+}
+
+//结束任务单,里面会根据任务的故障等级修正雷达管理模块的状态和任务单的状态
+Error_manager Velodyne_manager::end_task()
+{
+	m_execute_condition.notify_all(false);
+
+	if ( m_velodyne_manager_status == E_BUSY ||
+	m_velodyne_manager_status == E_ISSUED_SCAN ||
+	m_velodyne_manager_status == E_WAIT_SCAN ||
+	m_velodyne_manager_status == E_ISSUED_DETECT ||
+	m_velodyne_manager_status == E_WAIT_DETECT )
+	{
+		m_velodyne_manager_status = E_READY;
+	}
+	//else 状态不变
+
+	//在结束任务单时,将雷达任务状态改为 TASK_OVER 已结束
+	if(mp_velodyne_manager_task !=NULL)
+	{
+		//判断任务单的错误等级,
+		if ( mp_velodyne_manager_task->get_task_error_manager().get_error_level() < Error_level::MINOR_ERROR)
+		{
+			//强制改为TASK_OVER,不管它当前在做什么。
+			mp_velodyne_manager_task->set_task_statu(TASK_OVER);
+		}
+		else
+		{
+			//强制改为 TASK_ERROR,不管它当前在做什么。
+			mp_velodyne_manager_task->set_task_statu(TASK_ERROR);
+		}
+	}
+
+	return Error_code::SUCCESS;
+}
+
+//取消任务单,由发送方提前取消任务单
+Error_manager Velodyne_manager::cancel_task(Task_Base* p_velodyne_manager_task)
+{
+	//关闭子线程
+	m_execute_condition.notify_all(false);
+	//确保内部线程已经停下
+	while (m_execute_condition.is_working())
+	{
+	}
+
+	//强制改为 TASK_DEAD,不管它当前在做什么。
+	mp_velodyne_manager_task->set_task_statu(TASK_DEAD);
+
+	if (m_velodyne_manager_status == E_BUSY ||
+		m_velodyne_manager_status == E_ISSUED_SCAN ||
+		m_velodyne_manager_status == E_WAIT_SCAN ||
+		m_velodyne_manager_status == E_ISSUED_DETECT ||
+		m_velodyne_manager_status == E_WAIT_DETECT)
+	{
+		m_velodyne_manager_status = E_READY;
+	}
+	//else 状态不变
+
+	return Error_code::SUCCESS;
+}
+
+//检查雷达状态,是否正常运行
+Error_manager Velodyne_manager::check_status()
+{
+	if (m_velodyne_manager_status == E_READY)
+	{
+		return Error_code::SUCCESS;
+	}
+	else if (m_velodyne_manager_status == E_BUSY ||
+			 m_velodyne_manager_status == E_ISSUED_SCAN ||
+			 m_velodyne_manager_status == E_WAIT_SCAN ||
+			 m_velodyne_manager_status == E_ISSUED_DETECT ||
+			 m_velodyne_manager_status == E_WAIT_DETECT)
+	{
+		return Error_manager(Error_code::VELODYNE_MANAGER_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
+							 " Velodyne_manager::check_status error ");
+	}
+	else
+	{
+		return Error_manager(Error_code::VELODYNE_MANAGER_STATUS_ERROR, Error_level::MINOR_ERROR,
+							 " Velodyne_manager::check_status error ");
+	}
+	return Error_code::SUCCESS;
+}
+
+void Velodyne_manager::collect_cloud_thread_fun()
+{
+	LOG(INFO) << " Velodyne_manager::collect_cloud_thread_fun() start "<< this;
+	Error_manager t_error;
+	Error_manager t_result;
+
+	while (m_collect_cloud_condition.is_alive())
+	{
+		//暂时固定为一个扫描周期, 就循环一次
+		//后期可以根据每个小雷达的刷新情况, 实时更改总点云.....
+		m_collect_cloud_condition.wait_for_millisecond(VLP16_SCAN_CYCLE_MS);
+		if ( m_collect_cloud_condition.is_alive() )
+		{
+			{
+				//全局加锁, 并清空点云.
+				std::unique_lock<std::mutex> t_lock(m_cloud_collection_mutex);
+				mp_cloud_collection->clear();
+
+				//重新收集最近的点云, 不允许阻塞
+				// added by yct, 测试雷达功能
+//				int get_cloud_count=0;
+				for (auto iter = m_velodyne_lidar_device_map.begin(); iter != m_velodyne_lidar_device_map.end(); ++iter)
+				{
+					t_error = iter->second->get_last_cloud(mp_cloud_collection, std::chrono::steady_clock::now());
+					if ( t_error != Error_code::SUCCESS )
+					{
+						t_result.compare_and_cover_error(t_error);
+//						LOG(WARNING) << "cloud timeout: "<<get_cloud_count;
+					}
+//                    get_cloud_count++;
+				}
+
+				if ( t_result == SUCCESS && mp_cloud_collection->size()>0 )
+				{
+					m_cloud_updata_time = std::chrono::system_clock::now();
+					//成功则唤醒预测算法
+					update_region_cloud();
+				}
+				else
+				{
+					mp_cloud_collection->clear();
+//					LOG(WARNING) << t_result.to_string();
+				}
+			}
+		}
+        t_result.error_manager_clear_all();
+	}
+	LOG(INFO) << " Velodyne_manager::collect_cloud_thread_fun() end "<< this;
+	return;
+}
+
+//更新点云,自行计算
+Error_manager Velodyne_manager::update_region_cloud()
+{
+	for (auto iter = m_ground_region_map.begin(); iter != m_ground_region_map.end(); ++iter)
+	{
+		iter->second->update_cloud(mp_cloud_collection);
+	}
+	return Error_code::SUCCESS;
+}
+
+//执行外界任务的执行函数
+void Velodyne_manager::execute_thread_fun()
+{
+	LOG(INFO) << " Velodyne_manager::execute_thread_fun() start "<< this;
+	Error_manager t_error;
+	Common_data::Car_wheel_information t_car_wheel_information;
+
+	//雷达管理的独立线程,负责控制管理所有的雷达。
+	while (m_execute_condition.is_alive())
+	{
+		m_execute_condition.wait();
+		if ( m_execute_condition.is_alive() )
+		{
+			std::this_thread::yield();
+			//重新循环必须清除错误码.
+			t_error.error_manager_clear_all();
+
+			if ( mp_velodyne_manager_task == NULL )
+			{
+				//忽略任务, 直接停止线程
+				m_velodyne_manager_status = E_READY;
+				m_execute_condition.notify_all(false);
+			}
+
+			//velodyne内部全自动运行, 只需要根据时间去获取想要的就行了.
+			//目前楚天是唯一的预测算法, 如果后续有多个出入口,则使用任务单的终端id来获取指定的.
+			if ( m_ground_region_map.size() > 0 && m_ground_region_map.find(mp_velodyne_manager_task->get_terminal_id()) != m_ground_region_map.end())
+			{
+				t_error = m_ground_region_map[mp_velodyne_manager_task->get_terminal_id()]->get_current_wheel_information(&t_car_wheel_information, mp_velodyne_manager_task->get_command_time());
+				if ( t_error == Error_code::SUCCESS )
+				{
+					//添加车轮的预测结果
+					mp_velodyne_manager_task->set_car_wheel_information(t_car_wheel_information);
+					//正常完成任务
+					end_task();
+				}
+				else
+				{
+					//如果在指令时间1秒后都没有成功获取结果, 返回错误原因
+					if ( std::chrono::system_clock::now() - m_ground_region_map[mp_velodyne_manager_task->get_terminal_id()]->get_detect_update_time() < std::chrono::milliseconds(VELODYNE_MANAGER_EXECUTE_TIMEOUT_MS)  )
+					{
+						//没有超时, 那么就等1ms, 然后重新循环
+						std::this_thread::sleep_for(std::chrono::milliseconds(1));
+						std::this_thread::yield();
+					}
+					else
+					{
+						//因为故障,而提前结束任务.
+						mp_velodyne_manager_task->compare_and_cover_task_error_manager(t_error);
+						end_task();
+					}
+
+				}
+			}
+
+		}
+	}
+	LOG(INFO) << " Velodyne_manager::execute_thread_fun() end "<< this;
+	return;
+}
+

+ 16 - 14
velodyne_lidar/velodyne_manager.h

@@ -1,8 +1,10 @@
 /*
  * @Description: velodyne多线雷达管理类
+ * 非分布式模式下,将采集所有雷达点云,并下发给所有区域
+ * 分布式模式下,程序各自独立,分别只实例化一个设定的区域,以及相应雷达
  * @Author: yct
  * @Date: 2021-07-23 16:37:33
- * @LastEditTime: 2021-07-28 16:10:45
+ * @LastEditTime: 2021-07-30 17:01:29
  * @LastEditors: yct
  */
 
@@ -12,6 +14,7 @@
 #include <map>
 
 #include "../tool/singleton.h"
+#include "../tool/point_tool.h"
 #include "../error_code/error_code.h"
 
 #include "./velodyne_driver/velodyne_lidar_device.h"
@@ -23,9 +26,10 @@ class Velodyne_manager : public Singleton<Velodyne_manager>
 {
     // 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
     friend class Singleton<Velodyne_manager>;
-    //万集管理任务超时时间1000ms,
+public:
+    //velodyne管理任务超时时间1000ms,
     #define VELODYNE_MANAGER_EXECUTE_TIMEOUT_MS 1000
-    //万集配置参数的默认路径
+    //velodyne配置参数的默认路径
     #define VELODYNE_MANAGER_PARAMETER_PATH "../setting/velodyne_manager.prototxt"
 	//雷达管理的状态
 	enum Velodyne_manager_status
@@ -42,21 +46,20 @@ class Velodyne_manager : public Singleton<Velodyne_manager>
 
 		E_FAULT					= 10,	//故障
 	};
-public:
     // 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
     Velodyne_manager(const Velodyne_manager &) = delete;
     Velodyne_manager &operator=(const Velodyne_manager &) = delete;
     ~Velodyne_manager() = default;
 
     //初始化 雷达 管理模块。如下三选一
-	Error_manager velodyne_manager_init();
+	Error_manager velodyne_manager_init(int terminal = 0);
 	//初始化 雷达 管理模块。从文件读取
-	Error_manager velodyne_manager_init_from_protobuf(std::string prototxt_path);
+	Error_manager velodyne_manager_init_from_protobuf(std::string prototxt_path, int terminal = 0);
 	//初始化 雷达 管理模块。从protobuf读取
-	Error_manager velodyne_manager_init_from_protobuf(velodyne::velodyneManagerParams & velodyne_parameters);
+	Error_manager velodyne_manager_init_from_protobuf(velodyne::velodyneManagerParams &velodyne_parameters, int terminal = 0);
 
-    // 反初始化
-    Error_manager Velodyne_manager_uninit();
+	// 反初始化
+	Error_manager Velodyne_manager_uninit();
 
 	//对外的接口函数,负责接受并处理任务单,
 	Error_manager execute_task(Task_Base* p_velodyne_manager_task);
@@ -68,7 +71,7 @@ public:
 	//检查雷达状态,是否正常运行
 	Error_manager check_status();
 	//判断是否为待机,如果已经准备好,则可以执行任务。
-	bool is_ready();
+	bool is_ready() { return m_velodyne_manager_status == E_READY; }
 
 public://get or set member variable
 	Velodyne_manager_status get_status() { return m_velodyne_manager_status; }
@@ -78,10 +81,8 @@ public://get or set member variable
 protected://member functions
 	//自动收集点云的线程函数
 	void collect_cloud_thread_fun();
-	//开始自动预测的算法线程
-	Error_manager start_auto_detect();
-	//关闭自动预测的算法线程
-	Error_manager stop_auto_detect();
+	//更新点云,自行计算
+	Error_manager update_region_cloud();
 
 	//执行外界任务的执行函数
 	void execute_thread_fun();
@@ -90,6 +91,7 @@ private:
     // 父类的构造函数必须保护,子类的构造函数必须私有。
     Velodyne_manager() = default;
 
+	int m_terminal_id;
 	Velodyne_manager_status m_velodyne_manager_status; //velodyne管理状态
 
 	std::map<int, Velodyne_lidar_device *> 		m_velodyne_lidar_device_map; 		// velodyne雷达实例指针数组, 内存由本类管理

+ 3 - 3
velodyne_lidar/velodyne_manager_task.cpp

@@ -16,7 +16,7 @@ Velodyne_manager_task::~Velodyne_manager_task()
 }
 
 //初始化函数
-Error_manager Velodyne_manager_task::task_init(int terminal_id, std::chrono::steady_clock::time_point command_time	)
+Error_manager Velodyne_manager_task::task_init(int terminal_id, std::chrono::system_clock::time_point command_time	)
 {
 	m_task_statu = TASK_CREATED;
 	m_task_statu_information.clear();
@@ -32,7 +32,7 @@ Error_manager Velodyne_manager_task::task_init(Task_statu task_statu,
 						void* p_tast_receiver,
 						std::chrono::milliseconds task_over_time,
 						int terminal_id,
-						std::chrono::steady_clock::time_point command_time
+						std::chrono::system_clock::time_point command_time
 )
 {
 	m_task_statu = task_statu;
@@ -51,7 +51,7 @@ int Velodyne_manager_task::get_terminal_id()
 {
 	return m_terminal_id;
 }
-std::chrono::steady_clock::time_point Velodyne_manager_task::get_command_time()
+std::chrono::system_clock::time_point Velodyne_manager_task::get_command_time()
 {
 	return m_command_time;
 }

+ 7 - 7
velodyne_lidar/velodyne_manager_task.h

@@ -1,5 +1,5 @@
-#ifndef WJ_LIDAR_TASK_HH
-#define WJ_LIDAR_TASK_HH
+#ifndef VELODYNE_MANAGER_TASK_HH
+#define VELODYNE_MANAGER_TASK_HH
 #include <string.h>
 #include <mutex>
 #include <atomic>
@@ -19,17 +19,17 @@ public:
     // 析构
     ~Velodyne_manager_task();
 	//初始化函数
-	Error_manager task_init(int terminal_id, std::chrono::steady_clock::time_point command_time	);
+	Error_manager task_init(int terminal_id, std::chrono::system_clock::time_point command_time	);
 	Error_manager task_init(Task_statu task_statu,
 							std::string task_statu_information,
 							void* p_tast_receiver,
 							std::chrono::milliseconds task_over_time,
 							int terminal_id,
-							std::chrono::steady_clock::time_point command_time
+							std::chrono::system_clock::time_point command_time
 	);
 public://get or set member variable
 	int get_terminal_id();
-	std::chrono::steady_clock::time_point get_command_time();
+	std::chrono::system_clock::time_point get_command_time();
 	Common_data::Car_wheel_information get_car_wheel_information();
 	void set_car_wheel_information(Common_data::Car_wheel_information car_wheel_information);
 
@@ -37,10 +37,10 @@ private:
 	//终端id
 	int 										m_terminal_id;
 	//下发指令的时间点. 从command_time提前一个扫描周期, 然后取最新的点
-	std::chrono::steady_clock::time_point 		m_command_time;
+	std::chrono::system_clock::time_point 		m_command_time;
     // 测量结果
     Common_data::Car_wheel_information			m_car_wheel_information;
 
 };
 
-#endif // !WJ_LIDAR_TASK_HH
+#endif // !VELODYNE_MANAGER_TASK_HH

+ 10 - 10
wanji_lidar/region_worker.cpp

@@ -5,7 +5,7 @@
 //#include "plc_data.h"
 
 // 测量结果滤波,不影响现有结构
-#include "measure_filter.h"
+#include "../tool/measure_filter.h"
 
 Region_worker::Region_worker()
 {
@@ -14,7 +14,7 @@ Region_worker::Region_worker()
 	mp_cloud_collection_mutex = NULL;
 	mp_cloud_collection = NULL;
 
-	m_detect_updata_time = std::chrono::steady_clock::now() - std::chrono::hours(1);
+	m_detect_updata_time = std::chrono::system_clock::now() - std::chrono::hours(1);
 
 	mp_auto_detect_thread = NULL;
 
@@ -84,7 +84,7 @@ Error_manager Region_worker::detect_wheel_result_ex(std::mutex* p_cloud_mutex, p
 
 //外部调用获取新的车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会等待车轮定位信息刷新, 直到超时, (内置while)
 Error_manager Region_worker::get_new_wheel_information_and_wait(Common_data::Car_wheel_information* p_car_wheel_information,
-												 std::chrono::steady_clock::time_point command_time, int timeout_ms)
+												 std::chrono::system_clock::time_point command_time, int timeout_ms)
 {
 	if ( p_car_wheel_information == NULL )
 	{
@@ -92,7 +92,7 @@ Error_manager Region_worker::get_new_wheel_information_and_wait(Common_data::Car
 							 "  POINTER IS NULL ");
 	}
 	//判断是否超时
-	while (std::chrono::steady_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
+	while (std::chrono::system_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
 	{
 		//获取指令时间之后的信息, 如果没有就会循环
 		if(m_detect_updata_time > command_time  )
@@ -112,7 +112,7 @@ Error_manager Region_worker::get_new_wheel_information_and_wait(Common_data::Car
 
 //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
 Error_manager Region_worker::get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
-											std::chrono::steady_clock::time_point command_time)
+											std::chrono::system_clock::time_point command_time)
 {
 	if ( p_car_wheel_information == NULL )
 	{
@@ -133,7 +133,7 @@ Error_manager Region_worker::get_current_wheel_information(Common_data::Car_whee
 }
 //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
 Error_manager Region_worker::get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
-										 std::chrono::steady_clock::time_point command_time)
+										 std::chrono::system_clock::time_point command_time)
 {
 	if ( p_car_wheel_information == NULL )
 	{
@@ -159,7 +159,7 @@ Region_worker::Region_worker_status Region_worker::get_status()
 	return m_region_worker_status;
 }
 
-std::chrono::steady_clock::time_point Region_worker::get_detect_updata_time()
+std::chrono::system_clock::time_point Region_worker::get_detect_updata_time()
 {
 	return m_detect_updata_time;
 }
@@ -220,11 +220,11 @@ void Region_worker::auto_detect_thread_fun()
 //            if(m_index==5)
 //			    LOG(INFO) << " huli test :::: " << " mp_cloud_collection->size() = " << mp_cloud_collection->size();
 //
-//			auto start   = std::chrono::steady_clock::now();
+//			auto start   = std::chrono::system_clock::now();
 
 			t_error = detect_wheel_result_ex(mp_cloud_collection_mutex, mp_cloud_collection, m_car_wheel_information);
 
-//			auto end   = std::chrono::steady_clock::now();
+//			auto end   = std::chrono::system_clock::now();
 //			auto duration = std::chrono::duration_cast<std::chrono::microseconds>(end - start);
 //			std::cout <<  "花费了"
 //				 << double(duration.count()*1000) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den   << "毫秒" << std::endl;
@@ -255,7 +255,7 @@ void Region_worker::auto_detect_thread_fun()
 			}
 
 			//无论结果如何,都要刷新时间, 表示这次定位已经执行了.
-			m_detect_updata_time = std::chrono::steady_clock::now();
+			m_detect_updata_time = std::chrono::system_clock::now();
 //            if(m_index==5)
 //                LOG(INFO) << "before filter";
 			// 测量正确,更新到滤波器

+ 6 - 6
wanji_lidar/region_worker.h

@@ -71,19 +71,19 @@ public:
 
 	//外部调用获取新的车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会等待车轮定位信息刷新, 直到超时, (内置while)
 	Error_manager get_new_wheel_information_and_wait(Common_data::Car_wheel_information* p_car_wheel_information,
-													 std::chrono::steady_clock::time_point command_time, int timeout_ms=1500);
+													 std::chrono::system_clock::time_point command_time, int timeout_ms=1500);
 
 	//外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
 	Error_manager get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
-												std::chrono::steady_clock::time_point command_time);
+												std::chrono::system_clock::time_point command_time);
 	//外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
 	Error_manager get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
-											 std::chrono::steady_clock::time_point command_time);
+											 std::chrono::system_clock::time_point command_time);
 
 public:
 	Region_worker_status get_status();
 
-	std::chrono::steady_clock::time_point get_detect_updata_time();
+	std::chrono::system_clock::time_point get_detect_updata_time();
 
 protected:
 	static cv::RotatedRect create_rotate_rect(float length,float width,float angle,float x,float y);
@@ -104,7 +104,7 @@ protected:
 	std::mutex*	 								mp_cloud_collection_mutex;       // 点云更新互斥锁, 内存由上级管理
 	pcl::PointCloud<pcl::PointXYZ>::Ptr 		mp_cloud_collection;			//扫描点的点云集合, 内存由上级管理
 	Common_data::Car_wheel_information			m_car_wheel_information;		//车轮的定位结果,
-	std::chrono::steady_clock::time_point		m_detect_updata_time;			//定位结果的更新时间.
+	std::chrono::system_clock::time_point		m_detect_updata_time;			//定位结果的更新时间.
 
 	std::thread*        						mp_auto_detect_thread;   		//自动预测的线程指针,内存由本类管理
 	Thread_condition							m_auto_detect_condition;		//自动预测的条件变量
@@ -116,7 +116,7 @@ protected:
 //    pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud;             // 自动区域检测用点云
 //    std::atomic<bool> mb_cloud_updated;                      // 点云更新指标
 ////
-////    std::chrono::steady_clock::time_point m_update_plc_time; // 更新plc状态时刻
+////    std::chrono::system_clock::time_point m_update_plc_time; // 更新plc状态时刻
 ////    int m_last_sent_code;                              // 上次写入plc的状态值
 ////    int m_last_read_code;                              // 上次检查获得的状态值
 ////    int m_last_border_status;				// 上次超界提示

+ 1 - 1
wanji_lidar/wanji_manager.cpp

@@ -422,7 +422,7 @@ void Wanji_manager::execute_thread_fun()
 				else
 				{
 					//如果在指令时间1秒后都没有成功获取结果, 返回错误原因
-					if ( std::chrono::steady_clock::now() - m_region_worker_map[mp_wanji_manager_task->get_terminal_id()]->get_detect_updata_time() < std::chrono::milliseconds(WANJI_MANAGER_EXECUTE_TIMEOUT_MS)  )
+					if ( std::chrono::system_clock::now() - m_region_worker_map[mp_wanji_manager_task->get_terminal_id()]->get_detect_updata_time() < std::chrono::milliseconds(WANJI_MANAGER_EXECUTE_TIMEOUT_MS)  )
 					{
 						//没有超时, 那么就等1ms, 然后重新循环
 						std::this_thread::sleep_for(std::chrono::milliseconds(1));

+ 3 - 3
wanji_lidar/wanji_manager_task.cpp

@@ -16,7 +16,7 @@ Wanji_manager_task::~Wanji_manager_task()
 }
 
 //初始化函数
-Error_manager Wanji_manager_task::task_init(int terminal_id, std::chrono::steady_clock::time_point command_time	)
+Error_manager Wanji_manager_task::task_init(int terminal_id, std::chrono::system_clock::time_point command_time	)
 {
 	m_task_statu = TASK_CREATED;
 	m_task_statu_information.clear();
@@ -32,7 +32,7 @@ Error_manager Wanji_manager_task::task_init(Task_statu task_statu,
 						void* p_tast_receiver,
 						std::chrono::milliseconds task_over_time,
 						int terminal_id,
-						std::chrono::steady_clock::time_point command_time
+						std::chrono::system_clock::time_point command_time
 )
 {
 	m_task_statu = task_statu;
@@ -51,7 +51,7 @@ int Wanji_manager_task::get_terminal_id()
 {
 	return m_terminal_id;
 }
-std::chrono::steady_clock::time_point Wanji_manager_task::get_command_time()
+std::chrono::system_clock::time_point Wanji_manager_task::get_command_time()
 {
 	return m_command_time;
 }

+ 7 - 7
wanji_lidar/wanji_manager_task.h

@@ -1,5 +1,5 @@
-#ifndef WJ_LIDAR_TASK_HH
-#define WJ_LIDAR_TASK_HH
+#ifndef WANJI_MANAGER_TASK_HH
+#define WANJI_MANAGER_TASK_HH
 #include <string.h>
 #include <mutex>
 #include <atomic>
@@ -19,17 +19,17 @@ public:
     // 析构
     ~Wanji_manager_task();
 	//初始化函数
-	Error_manager task_init(int terminal_id, std::chrono::steady_clock::time_point command_time	);
+	Error_manager task_init(int terminal_id, std::chrono::system_clock::time_point command_time	);
 	Error_manager task_init(Task_statu task_statu,
 							std::string task_statu_information,
 							void* p_tast_receiver,
 							std::chrono::milliseconds task_over_time,
 							int terminal_id,
-							std::chrono::steady_clock::time_point command_time
+							std::chrono::system_clock::time_point command_time
 	);
 public://get or set member variable
 	int get_terminal_id();
-	std::chrono::steady_clock::time_point get_command_time();
+	std::chrono::system_clock::time_point get_command_time();
 	Common_data::Car_wheel_information get_car_wheel_information();
 	void set_car_wheel_information(Common_data::Car_wheel_information car_wheel_information);
 
@@ -37,10 +37,10 @@ private:
 	//终端id
 	int 										m_terminal_id;
 	//下发指令的时间点. 从command_time提前一个扫描周期, 然后取最新的点
-	std::chrono::steady_clock::time_point 		m_command_time;
+	std::chrono::system_clock::time_point 		m_command_time;
     // 测量结果
     Common_data::Car_wheel_information			m_car_wheel_information;
 
 };
 
-#endif // !WJ_LIDAR_TASK_HH
+#endif // !WANJI_MANAGER_TASK_HH