浏览代码

解决因点云指针未初始化导致的崩溃问题。
velo manager 与整个系统已通过包括通信的测试

yct 3 年之前
父节点
当前提交
7534207526

+ 24 - 7
main.cpp

@@ -43,7 +43,7 @@ GOOGLE_GLOG_DLL_DECL void shut_down_logging(const char* data, int size)
 
 void test_whole_process()
 {
-	System_executor::get_instance_references().execute_for_measure("key_for_test_only", 1, std::chrono::system_clock::now());
+	System_executor::get_instance_references().execute_for_measure("key_for_test_only", 0, std::chrono::system_clock::now());
 }
 
 int main(int argc,char* argv[])
@@ -52,7 +52,7 @@ int main(int argc,char* argv[])
 	Error_manager t_result ;
 
 
-	const char* logPath = "./";
+	const char* logPath = "./log/";
 	google::InitGoogleLogging("LidarMeasurement");
 	google::SetStderrLogging(google::INFO);
 	google::SetLogDestination(0, logPath);
@@ -78,16 +78,33 @@ int main(int argc,char* argv[])
 	// 初始化
 	// 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;
+	Error_manager ec = Velodyne_manager::get_instance_references().velodyne_manager_init(t_terminal_id);
+	std::cout << "veodyne_manager = " << Velodyne_manager::get_instance_references().check_status().to_string() << std::endl;
+	if(ec != SUCCESS)
+	{
+		LOG(ERROR) << "velodyne_manager init failed: " << ec.to_string();
+		return -1;
+	}
 
-	System_executor::get_instance_references().system_executor_init(4, t_terminal_id);
+	ec = 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;
+	if(ec != SUCCESS)
+	{
+		LOG(ERROR) << "system executor init failed: " << ec.to_string();
+		return -1;
+	}
 
-	System_communication::get_instance_references().communication_init();
+	usleep(1000 * 500);
+
+	ec = System_communication::get_instance_references().communication_init();
+	if(ec != SUCCESS)
+	{
+		LOG(ERROR) << "system communication init failed: " << ec.to_string();
+		return -1;
+	}
 
 	// prev_test_pred_task();
-//	test_whole_process();
+	// test_whole_process();
 //    usleep(1000*5000);
     char ch='x' ;
     while(ch != 'q') {

+ 26 - 25
message/message_base.pb.cc

@@ -345,7 +345,7 @@ void AddDescriptorsImpl() {
       "\001(\002\0223\n\020parkspace_status\030\010 \001(\0162\031.message."
       "Parkspace_status\022#\n\010car_info\030\t \001(\0132\021.mes"
       "sage.Car_info\022\022\n\nentry_time\030\n \001(\t\022\022\n\nlea"
-      "ve_time\030\013 \001(\t*\253\010\n\014Message_type\022\r\n\teBase_"
+      "ve_time\030\013 \001(\t*\304\010\n\014Message_type\022\r\n\teBase_"
       "msg\020\000\022\020\n\014eCommand_msg\020\001\022\026\n\022eLocate_statu"
       "s_msg\020\021\022\027\n\023eLocate_request_msg\020\022\022\030\n\024eLoc"
       "ate_response_msg\020\023\022\034\n\030eLocate_sift_reque"
@@ -372,32 +372,32 @@ void AddDescriptorsImpl() {
       "ual_operation_msg\020\260\001\022\"\n\035eProcess_manual_"
       "operation_msg\020\261\001\022\037\n\032eGround_detect_reque"
       "st_msg\020\360\001\022 \n\033eGround_detect_response_msg"
-      "\020\361\001*\231\001\n\014Communicator\022\n\n\006eEmpty\020\000\022\t\n\005eMai"
-      "n\020\001\022\016\n\teTerminor\020\200\002\022\017\n\neParkspace\020\200\004\022\016\n\t"
-      "eMeasurer\020\200\006\022\032\n\025eMeasurer_sift_server\020\201\006"
-      "\022\016\n\teDispatch\020\200\010\022\025\n\020eGround_measurer\020\200\036*"
-      "*\n\014Process_type\022\014\n\010eStoring\020\001\022\014\n\010ePickin"
-      "g\020\002*e\n\013Error_level\022\n\n\006NORMAL\020\000\022\024\n\020NEGLIG"
-      "IBLE_ERROR\020\001\022\017\n\013MINOR_ERROR\020\002\022\017\n\013MAJOR_E"
-      "RROR\020\003\022\022\n\016CRITICAL_ERROR\020\004*q\n\020Parkspace_"
-      "status\022\024\n\020eParkspace_empty\020\000\022\027\n\023eParkspa"
-      "ce_occupied\020\001\022\030\n\024eParkspace_reserverd\020\002\022"
-      "\024\n\020eParkspace_error\020\003*(\n\tDirection\022\014\n\010eF"
-      "orward\020\001\022\r\n\teBackward\020\002*\335\002\n\tStep_type\022\017\n"
-      "\013eAlloc_step\020\000\022\021\n\reMeasure_step\020\001\022\021\n\reCo"
-      "mpare_step\020\002\022\022\n\016eDispatch_step\020\003\022\021\n\reCon"
-      "firm_step\020\004\022\020\n\014eSearch_step\020\005\022\016\n\neWait_s"
-      "tep\020\006\022\021\n\reRelease_step\020\007\022\r\n\teComplete\020\010\022"
-      "\025\n\021eBackConfirm_step\020\t\022\026\n\022eBack_compare_"
-      "step\020\n\022\025\n\021eBackMeasure_step\020\013\022\023\n\017eBackAl"
-      "loc_step\020\014\022\022\n\016eBackWait_step\020\r\022\026\n\022eBackD"
-      "ispatch_step\020\016\022\024\n\020eBackSearch_step\020\017\022\021\n\r"
-      "eBackComplete\020\020*C\n\nStep_statu\022\014\n\010eWaitin"
-      "g\020\000\022\014\n\010eWorking\020\001\022\n\n\006eError\020\002\022\r\n\teFinish"
-      "ed\020\003"
+      "\020\361\001\022\027\n\022eGround_status_msg\020\362\001*\231\001\n\014Communi"
+      "cator\022\n\n\006eEmpty\020\000\022\t\n\005eMain\020\001\022\016\n\teTermino"
+      "r\020\200\002\022\017\n\neParkspace\020\200\004\022\016\n\teMeasurer\020\200\006\022\032\n"
+      "\025eMeasurer_sift_server\020\201\006\022\016\n\teDispatch\020\200"
+      "\010\022\025\n\020eGround_measurer\020\200\036**\n\014Process_type"
+      "\022\014\n\010eStoring\020\001\022\014\n\010ePicking\020\002*e\n\013Error_le"
+      "vel\022\n\n\006NORMAL\020\000\022\024\n\020NEGLIGIBLE_ERROR\020\001\022\017\n"
+      "\013MINOR_ERROR\020\002\022\017\n\013MAJOR_ERROR\020\003\022\022\n\016CRITI"
+      "CAL_ERROR\020\004*q\n\020Parkspace_status\022\024\n\020ePark"
+      "space_empty\020\000\022\027\n\023eParkspace_occupied\020\001\022\030"
+      "\n\024eParkspace_reserverd\020\002\022\024\n\020eParkspace_e"
+      "rror\020\003*(\n\tDirection\022\014\n\010eForward\020\001\022\r\n\teBa"
+      "ckward\020\002*\335\002\n\tStep_type\022\017\n\013eAlloc_step\020\000\022"
+      "\021\n\reMeasure_step\020\001\022\021\n\reCompare_step\020\002\022\022\n"
+      "\016eDispatch_step\020\003\022\021\n\reConfirm_step\020\004\022\020\n\014"
+      "eSearch_step\020\005\022\016\n\neWait_step\020\006\022\021\n\reRelea"
+      "se_step\020\007\022\r\n\teComplete\020\010\022\025\n\021eBackConfirm"
+      "_step\020\t\022\026\n\022eBack_compare_step\020\n\022\025\n\021eBack"
+      "Measure_step\020\013\022\023\n\017eBackAlloc_step\020\014\022\022\n\016e"
+      "BackWait_step\020\r\022\026\n\022eBackDispatch_step\020\016\022"
+      "\024\n\020eBackSearch_step\020\017\022\021\n\reBackComplete\020\020"
+      "*C\n\nStep_statu\022\014\n\010eWaiting\020\000\022\014\n\010eWorking"
+      "\020\001\022\n\n\006eError\020\002\022\r\n\teFinished\020\003"
   };
   ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
-      descriptor, 2924);
+      descriptor, 2949);
   ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
     "message_base.proto", &protobuf_RegisterTypes);
 }
@@ -452,6 +452,7 @@ bool Message_type_IsValid(int value) {
     case 177:
     case 240:
     case 241:
+    case 242:
       return true;
     default:
       return false;

+ 3 - 2
message/message_base.pb.h

@@ -118,11 +118,12 @@ enum Message_type {
   eEntrance_manual_operation_msg = 176,
   eProcess_manual_operation_msg = 177,
   eGround_detect_request_msg = 240,
-  eGround_detect_response_msg = 241
+  eGround_detect_response_msg = 241,
+  eGround_status_msg = 242
 };
 bool Message_type_IsValid(int value);
 const Message_type Message_type_MIN = eBase_msg;
-const Message_type Message_type_MAX = eGround_detect_response_msg;
+const Message_type Message_type_MAX = eGround_status_msg;
 const int Message_type_ARRAYSIZE = Message_type_MAX + 1;
 
 const ::google::protobuf::EnumDescriptor* Message_type_descriptor();

+ 1 - 0
message/message_base.proto

@@ -51,6 +51,7 @@ enum Message_type
 
     eGround_detect_request_msg=0xf0;        //地面雷达测量请求消息
     eGround_detect_response_msg=0xf1;       //地面雷达测量反馈消息
+    eGround_status_msg=0xf2;                //地面雷达状态消息
 }
 
 //通讯单元

+ 2 - 2
setting/communication.prototxt

@@ -3,8 +3,8 @@
 communication_parameters
 {
 
-  bind_string:"tcp://192.168.2.119:30010"
-  connect_string_vector:"tcp://192.168.2.119:30000"
+  bind_string:"tcp://192.168.2.113:30010"
+  connect_string_vector:"tcp://192.168.2.113:30000"
  # connect_string_vector:"tcp://192.168.2.166:9002"
 
   # connect_string_vector:"tcp://192.168.2.125:9876"

+ 1 - 0
setting/velodyne_manager.prototxt

@@ -33,4 +33,5 @@ region
 	minz:0.01
 	maxz:0.2
     region_id:0
+    lidar_ids:0
 }

+ 9 - 8
system/system_executor.cpp

@@ -236,14 +236,15 @@ Error_manager System_executor::encapsulate_send_status()
 	Error_manager t_error;
 	//创建一条状态消息
 	message::Ground_status_msg t_ground_status_msg;
-	t_ground_status_msg.mutable_base_info()->set_msg_type(message::Message_type::eLocate_status_msg);
+	t_ground_status_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_status_msg);
 	t_ground_status_msg.mutable_base_info()->set_timeout_ms(5000);
 	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,不做修改
+	// 创建各区域状态消息, 
+	// 注意!!!目前公共消息名字依旧使用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);
@@ -272,7 +273,7 @@ Error_manager System_executor::encapsulate_send_status()
 			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";
+				LOG(WARNING) << "lidar status "<<t_param.lidar_ids(j)<<" cannot be found, param error";
 			}else{
 				t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
 			}
@@ -454,7 +455,7 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 	//第3步, 等待任务单完成
 	if ( t_error != Error_code::SUCCESS )
 	{
-		LOG(INFO) << " Wanji_manager/Velodyne_manager  execute_task   error "<< this;
+		LOG(INFO) << " Velodyne_manager/Velodyne_manager  execute_task   error "<< this;
 	}
 	else
 	{
@@ -466,7 +467,7 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 		// 		//超时处理。取消任务。
 		// 		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_wanjestaui_manager_task is_over_time ");
 		// 		t_wanji_manager_task.set_task_error_manager(t_error);
 		// 	}
 		// 	else
@@ -494,8 +495,8 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 			if ( t_velodyne_manager_task.is_over_time() )
 			{
 				//超时处理。取消任务。
-				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,
+				Velodyne_manager::get_instance_pointer()->cancel_task(&t_velodyne_manager_task);
+				t_error.error_manager_reset(Error_code::VELODYNE_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
 											" t_velodyne_manager_task is_over_time ");
 				t_velodyne_manager_task.set_task_error_manager(t_error);
 			}
@@ -515,7 +516,7 @@ void System_executor::execute_for_measure(std::string command_info, int terminal
 		}
 		else
 		{
-		    LOG(INFO) << " wanji_manager_task error :::::::"  << t_velodyne_manager_task.get_task_error_manager().to_string() << this;
+		    LOG(INFO) << " velodyne_manager_task error :::::::"  << t_velodyne_manager_task.get_task_error_manager().to_string() << this;
 		}
 	}
 	t_result.compare_and_cover_error(t_error);

+ 126 - 3
tests/vlp16_driver_test.cpp

@@ -2,13 +2,14 @@
  * @Description: vlp16驱动测试
  * @Author: yct
  * @Date: 2021-07-26 14:11:26
- * @LastEditTime: 2021-07-30 16:25:35
+ * @LastEditTime: 2021-08-01 15:51:10
  * @LastEditors: yct
  */
 
 #include <iostream>
 #include <fstream>
 
+// velodyne driver seperation test
 #include "../velodyne_lidar/velodyne_driver/input.h"
 #include "../velodyne_lidar/velodyne_driver/rawdata.h"
 bool velo_driver_test()
@@ -64,7 +65,7 @@ bool velo_driver_test()
     return true;
 }
 
-// 初始化velodyne设备并获取点云
+// velodyne driver combination test
 #include "../velodyne_lidar/velodyne_driver/velodyne_lidar_device.h"
 void device_test()
 {
@@ -108,6 +109,7 @@ void device_test()
     t_device.uninit();
 }
 
+// ground region class function test
 #include "../velodyne_lidar/ground_region.h"
 #include "../tool/measure_filter.h"
 #include "../tool/point_tool.h"
@@ -189,11 +191,132 @@ void region_detect()
     }
 }
 
+// velodyne manager test
+#include "../velodyne_lidar/velodyne_manager.h"
+void velo_manager_test()
+{
+    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),
+								   0, std::chrono::system_clock::now());
+
+    Error_manager ec = Velodyne_manager::get_instance_references().velodyne_manager_init(0);
+	std::cout << "veodyne_manager = " << Velodyne_manager::get_instance_references().check_status().to_string() << std::endl;
+    if(ec != SUCCESS)
+    {
+        std::cout << "manager init failed: " << ec.to_string() << std::endl;
+        return;
+    }
+    usleep(1000 * 500);
+
+    Velodyne_manager::get_instance_references().execute_task(&t_velodyne_manager_task);
+    ec = Velodyne_manager::get_instance_references().execute_task(&t_velodyne_manager_task);
+    std::cout << "manager execute base check result: " << ec.to_string() << std::endl;
+
+    // 等待处理完成,来自于system_executor
+    while (t_velodyne_manager_task.is_task_end() == false)
+    {
+        if (t_velodyne_manager_task.is_over_time())
+        {
+            //超时处理。取消任务。
+            Velodyne_manager::get_instance_pointer()->cancel_task(&t_velodyne_manager_task);
+            ec.error_manager_reset(Error_code::VELODYNE_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
+                                        " t_velodyne_manager_task is_over_time ");
+            t_velodyne_manager_task.set_task_error_manager(ec);
+        }
+        else
+        {
+            //继续等待
+            std::this_thread::sleep_for(std::chrono::microseconds(1));
+            std::this_thread::yield();
+        }
+    }
+
+    //提取任务单 的错误码
+    ec = t_velodyne_manager_task.get_task_error_manager();
+    if (ec == Error_code::SUCCESS)
+    {
+        t_car_information_by_velodyne = t_velodyne_manager_task.get_car_wheel_information();
+    }
+    else
+    {
+        LOG(INFO) << " velodyne_manager_task error :::::::" << t_velodyne_manager_task.get_task_error_manager().to_string();
+    }
+
+    std::cout << "--------------------------"<< std::endl;
+    Velodyne_manager::get_instance_references().Velodyne_manager_uninit();
+}
+
+// 测试通信功能
+#include "../system/system_communication.h"
+#include "../system/system_executor.h"
+void message_test()
+{
+    nnxx::socket socket{nnxx::SP, nnxx::BUS};
+    // socket.bind("tcp://127.0.0.1:7000");
+    socket.connect("tcp://192.168.2.113:30010");
+    int n = 0;
+    message::Base_msg base_msg;
+
+    message::Ground_detect_request_msg t_ground_detect_request;
+    message::Base_info t_base_info;
+    t_base_info.set_msg_type(message::Message_type::eGround_detect_request_msg);
+    t_base_info.set_timeout_ms(4000);
+    t_base_info.set_sender(message::Communicator::eEmpty);
+    t_base_info.set_receiver(message::Communicator::eGround_measurer);
+    t_ground_detect_request.mutable_base_info()->CopyFrom(t_base_info);
+    t_ground_detect_request.set_command_key("key for test only");
+    t_ground_detect_request.set_terminal_id(0);
+
+    usleep(1000 * 1000);
+    std::cout << "try to send" << std::endl;
+    socket.send(t_ground_detect_request.SerializeAsString());
+    usleep(1000 * 100);
+
+    while (true)
+    {
+
+        // for (size_t i = 0; i < 10; i++)
+        // {
+            // 接收消息
+            std::string t_receive_string = socket.recv<std::string>(1);
+            if (t_receive_string.length() > 0)
+            {
+                bool result = base_msg.ParseFromString(t_receive_string);
+                // 接收并打印车位状态信息
+                std::cout << "====check result====================" << result << "============================" << std::endl;
+                std::cout << "cycle " << n << std::endl;
+                if (base_msg.base_info().msg_type() == message::Message_type::eGround_detect_response_msg)
+                {
+                    message::Ground_detect_response_msg t_ground_detect_response;
+                    std::cout << "----------------- check result -----------------" << std::endl;
+                    t_ground_detect_response.ParseFromString(t_receive_string);
+                    std::cout << "result: "<<t_ground_detect_response.DebugString()<< std::endl;
+                    // std::cout << sift_response.DebugString() << std::endl;
+                    // continue;
+                }else if(base_msg.base_info().msg_type() == message::Message_type::eGround_status_msg)
+                {
+                    message::Ground_status_msg t_status_msg;
+                    std::cout << "----------------- heartbeat -----------------" << std::endl;
+                    t_status_msg.ParseFromString(t_receive_string);
+                    std::cout << "heartbeat: "<<t_status_msg.DebugString()<< std::endl;
+                }
+            }
+        // }
+
+        // std::this_thread::yield();
+        n++;
+        usleep(1000 * 1);
+    }
+}
+
 int main()
 {
     // velo_driver_test();
     // device_test();
-    region_detect();
+    // region_detect();
+    // velo_manager_test();
+    message_test();
 
     return 0;
 }

+ 3 - 3
velodyne_lidar/ground_region.cpp

@@ -394,9 +394,9 @@ Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, d
             min_mean_loss = mean;
         }
     }
-    printf("z : %.3f  angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
-           center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
-           min_mean_loss);
+    // printf("z : %.3f  angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
+    //        center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
+    //        min_mean_loss);
     //m_detector->save_debug_data("/home/zx/zzw/catkin_ws/src/feature_extra/debug");
     return SUCCESS;
 }

+ 1 - 0
velodyne_lidar/velodyne_driver/velodyne_lidar_device.cpp

@@ -628,6 +628,7 @@ void Velodyne_lidar_device::execute_thread_fun()
 							std::unique_lock<std::mutex> lck(*tp_mutex);
 							{
 								std::lock_guard<std::mutex> lck(m_cloud_mutex);
+								// 转换lidar points为pcl点云
 								for (size_t i = 0; i < m_ring_cloud.size(); i++)
 								{
 									tp_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));

+ 24 - 5
velodyne_lidar/velodyne_manager.cpp

@@ -2,7 +2,7 @@
  * @Description: 
  * @Author: yct
  * @Date: 2021-07-23 16:39:04
- * @LastEditTime: 2021-07-30 17:25:21
+ * @LastEditTime: 2021-08-01 16:34:26
  * @LastEditors: yct
  */
 #include "velodyne_manager.h"
@@ -37,6 +37,7 @@ Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::ve
 							 " velodyne_manager::velodyne_manager_init_from_protobuf init repeat error ");
 	}
 	m_terminal_id = terminal;
+	mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
 
 	// 判断参数合法性
 	if(!velodyne_parameters.has_left_model_path() || ! velodyne_parameters.has_right_model_path())
@@ -80,7 +81,14 @@ Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::ve
 			m_ground_region_map[velodyne_parameters.region(i).region_id()] = p_ground_region;
 		}
 	}
-	
+	// 检查是否存在该区域
+	if(m_ground_region_map.find(m_terminal_id) == m_ground_region_map.end())
+	{
+		LOG(ERROR) << "param error, cannot find region "<<m_terminal_id;
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+							 " velodyne_manager::velodyne_manager_init_from_protobuf region defined in param cannot be found.");
+	}
+
 	//创建雷达设备
 	for(int i=0;i<velodyne_parameters.velodyne_lidars_size();++i)
 	{
@@ -97,6 +105,13 @@ Error_manager Velodyne_manager::velodyne_manager_init_from_protobuf(velodyne::ve
 			m_velodyne_lidar_device_map[velodyne_parameters.velodyne_lidars(i).lidar_id()] = p_velodyne_lidar_device;
 		}
 	}
+	// 检查设备与区域个数,不可为0
+	if(m_ground_region_map.size()<=0 || m_velodyne_lidar_device_map.size()<=0)
+	{
+		LOG(ERROR) << "param error, region or lidar size error";
+		return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
+							 " velodyne_manager::velodyne_manager_init_from_protobuf region or lidar size is 0");
+	}
 
 	//启动 收集点云的线程。默认 。
 	m_collect_cloud_condition.reset(false, false, false);
@@ -326,10 +341,9 @@ void Velodyne_manager::collect_cloud_thread_fun()
 					}
 //                    get_cloud_count++;
 				}
-
 				if ( t_result == SUCCESS && mp_cloud_collection->size()>0 )
 				{
-					m_cloud_updata_time = std::chrono::system_clock::now();
+					m_cloud_update_time = std::chrono::system_clock::now();
 					//成功则唤醒预测算法
 					update_region_cloud();
 				}
@@ -337,6 +351,9 @@ void Velodyne_manager::collect_cloud_thread_fun()
 				{
 					mp_cloud_collection->clear();
 //					LOG(WARNING) << t_result.to_string();
+					// // 未连接雷达时,可读入点云用于测试
+					// read_pointcloud("/home/youchen/extra_space/chutian/measure/puai_wj_2021/build/comb_calib.txt", mp_cloud_collection);
+					// update_region_cloud();
 				}
 			}
 		}
@@ -389,11 +406,13 @@ void Velodyne_manager::execute_thread_fun()
 				{
 					//添加车轮的预测结果
 					mp_velodyne_manager_task->set_car_wheel_information(t_car_wheel_information);
+					LOG(INFO) << "execute success with result: " << t_car_wheel_information.to_string();
 					//正常完成任务
 					end_task();
 				}
 				else
 				{
+					// LOG(WARNING) << "bbb";
 					//如果在指令时间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)  )
 					{
@@ -403,6 +422,7 @@ void Velodyne_manager::execute_thread_fun()
 					}
 					else
 					{
+						// LOG(WARNING) << "ccc";
 						//因为故障,而提前结束任务.
 						mp_velodyne_manager_task->compare_and_cover_task_error_manager(t_error);
 						end_task();
@@ -410,7 +430,6 @@ void Velodyne_manager::execute_thread_fun()
 
 				}
 			}
-
 		}
 	}
 	LOG(INFO) << " Velodyne_manager::execute_thread_fun() end "<< this;

+ 2 - 2
velodyne_lidar/velodyne_manager.h

@@ -4,7 +4,7 @@
  * 分布式模式下,程序各自独立,分别只实例化一个设定的区域,以及相应雷达
  * @Author: yct
  * @Date: 2021-07-23 16:37:33
- * @LastEditTime: 2021-07-30 17:01:29
+ * @LastEditTime: 2021-08-01 14:56:58
  * @LastEditors: yct
  */
 
@@ -100,7 +100,7 @@ private:
 	//velodyne雷达的自动功能, 定时收集所有点云, 然后通知detect去计算车轮信息.
 	std::mutex	 								m_cloud_collection_mutex;       // 点云更新互斥锁
 	pcl::PointCloud<pcl::PointXYZ>::Ptr 		mp_cloud_collection;			//扫描点的点云集合, 内存由本类管理
-	std::chrono::system_clock::time_point		m_cloud_updata_time;			//扫描点的更新时间.
+	std::chrono::system_clock::time_point		m_cloud_update_time;			//扫描点的更新时间.
 	std::thread*        						mp_collect_cloud_thread;   		//收集点云的线程指针,内存由本类管理
 	Thread_condition							m_collect_cloud_condition;		//收集点云的条件变量