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