99#include < sensor_msgs/msg/imu.hpp>
1010
1111struct cam_config {
12- bool onboard_imu = true ;// 使用内部IMU
13- bool extern_imu = false ;// 使用外部IMU,TODO
14- std::string imu_name = " onboard_imu" ;
15-
16- // 相机名称 + 设备ID
17- std::pair<std::string, int > CAM1 = {" cam_1" , 1 };
18- std::pair<std::string, int > CAM2 = {" cam_2" , -1 };
19- std::pair<std::string, int > CAM3 = {" cam_3" , -1 };
20- std::pair<std::string, int > CAM4 = {" cam_4" , -1 }; // -1 代表没有
21-
22- // 通信方式
23- int type = 0 ; // 0 --> 串口通信 1 --> 网口通信
24- std::string uart_dev = " /dev/ttyACM0" ;
25- std::string net_ip = " 192.168.1.188" ;
26- int net_port = 8888 ;
12+ bool onboard_imu = true ; // 使用内部IMU
13+ bool extern_imu = false ; // 使用外部IMU,TODO
14+ std::string imu_name = " onboard_imu" ;
15+
16+ // 相机名称 + 设备ID
17+ std::pair<std::string, int > CAM1 = {" cam_1" , 1 };
18+ std::pair<std::string, int > CAM2 = {" cam_2" , -1 };
19+ std::pair<std::string, int > CAM3 = {" cam_3" , -1 };
20+ std::pair<std::string, int > CAM4 = {" cam_4" , -1 }; // -1 代表没有
21+
22+ // 通信方式
23+ int type = 0 ; // 0 --> 串口通信 1 --> 网口通信
24+ std::string uart_dev = " /dev/ttyACM0" ;
25+ std::string net_ip = " 192.168.1.188" ;
26+ int net_port = 8888 ;
2727};
2828cam_config cfg;
2929
@@ -32,8 +32,9 @@ using namespace infinite_sense;
3232class CamDriver final : public rclcpp::Node {
3333 public:
3434 CamDriver ()
35- : Node(" ros2_cam_driver" ), node_handle_(std::shared_ptr<CamDriver>(this , [](auto *) {})), transport_(node_handle_) {
36-
35+ : Node(" ros2_cam_driver" ),
36+ node_handle_ (std::shared_ptr<CamDriver>(this , [](auto *) {})),
37+ transport_ (node_handle_) {
3738 if (cfg.type == 0 ) {
3839 synchronizer_.SetUsbLink (cfg.uart_dev , 921600 );
3940 } else if (cfg.type == 1 ) {
@@ -47,7 +48,6 @@ class CamDriver final : public rclcpp::Node {
4748 if (cfg.CAM3 .second >= 0 ) mv_cam_->SetParams ({{cfg.CAM3 .first , CAM_3}});
4849 if (cfg.CAM4 .second >= 0 ) mv_cam_->SetParams ({{cfg.CAM4 .first , CAM_4}});
4950
50-
5151 if (cfg.CAM1 .second >= 0 ) image_pubs_[cfg.CAM1 .first ] = transport_.advertise (cfg.CAM1 .first , 30 );
5252 if (cfg.CAM2 .second >= 0 ) image_pubs_[cfg.CAM2 .first ] = transport_.advertise (cfg.CAM2 .first , 30 );
5353 if (cfg.CAM3 .second >= 0 ) image_pubs_[cfg.CAM3 .first ] = transport_.advertise (cfg.CAM3 .first , 30 );
@@ -65,14 +65,22 @@ class CamDriver final : public rclcpp::Node {
6565 {
6666 using namespace std ::placeholders;
6767 if (cfg.onboard_imu ) {
68- Messenger::GetInstance ().SubStruct (
69- cfg.imu_name , std::bind (&CamDriver::ImuCallback, this , std::placeholders::_1, std::placeholders::_2));
68+ Messenger::GetInstance ().SubStruct (
69+ cfg.imu_name , std::bind (&CamDriver::ImuCallback, this , std::placeholders::_1, std::placeholders::_2));
7070 }
7171
72- if (cfg.CAM1 .second >= 0 ) Messenger::GetInstance ().SubStruct (cfg.CAM1 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
73- if (cfg.CAM2 .second >= 0 ) Messenger::GetInstance ().SubStruct (cfg.CAM2 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
74- if (cfg.CAM3 .second >= 0 ) Messenger::GetInstance ().SubStruct (cfg.CAM3 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
75- if (cfg.CAM4 .second >= 0 ) Messenger::GetInstance ().SubStruct (cfg.CAM4 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
72+ if (cfg.CAM1 .second >= 0 )
73+ Messenger::GetInstance ().SubStruct (
74+ cfg.CAM1 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
75+ if (cfg.CAM2 .second >= 0 )
76+ Messenger::GetInstance ().SubStruct (
77+ cfg.CAM2 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
78+ if (cfg.CAM3 .second >= 0 )
79+ Messenger::GetInstance ().SubStruct (
80+ cfg.CAM3 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
81+ if (cfg.CAM4 .second >= 0 )
82+ Messenger::GetInstance ().SubStruct (
83+ cfg.CAM4 .first , std::bind (&CamDriver::ImageCallback, this , std::placeholders::_1, std::placeholders::_2));
7684 }
7785 }
7886
@@ -104,7 +112,6 @@ class CamDriver final : public rclcpp::Node {
104112 image_pubs_[cam_data->name ].publish (image_msg);
105113 }
106114
107-
108115 private:
109116 infinite_sense::Synchronizer synchronizer_;
110117 SharedPtr node_handle_;
0 commit comments