@@ -11,17 +11,19 @@ class CamDriver final : public rclcpp::Node {
1111 : Node(" gige_driver" ),
1212 node_handle_ (std::shared_ptr<CamDriver>(this , [](auto *) {})),
1313 transport_ (node_handle_) {
14+ std::string camera_name = " cam_1" ;
15+ std::string imu_name = " imu_1" ;
1416 synchronizer_.SetUsbLink (" /dev/ttyACM0" , 921600 );
1517 const auto mv_cam = std::make_shared<infinite_sense::MvCam>();
16- mv_cam->SetParams ({{" cam_1 " , infinite_sense::CAM_1}});
18+ mv_cam->SetParams ({{camera_name , infinite_sense::CAM_1}});
1719 synchronizer_.UseSensor (mv_cam);
1820 synchronizer_.Start ();
19- imu_pub_ = this ->create_publisher <sensor_msgs::msg::Imu>(" imu/data " , 10 );
20- img_pub_ = transport_.advertise (" image_raw " , 10 );
21+ imu_pub_ = this ->create_publisher <sensor_msgs::msg::Imu>(imu_name , 10 );
22+ img_pub_ = transport_.advertise (camera_name , 10 );
2123 {
2224 using namespace std ::placeholders;
23- infinite_sense::Messenger::GetInstance ().SubStruct (" imu_1 " , std::bind (&CamDriver::ImuCallback, this , _1, _2));
24- infinite_sense::Messenger::GetInstance ().SubStruct (" cam_1 " , std::bind (&CamDriver::ImageCallback, this , _1, _2));
25+ infinite_sense::Messenger::GetInstance ().SubStruct (imu_name , std::bind (&CamDriver::ImuCallback, this , _1, _2));
26+ infinite_sense::Messenger::GetInstance ().SubStruct (camera_name , std::bind (&CamDriver::ImageCallback, this , _1, _2));
2527 }
2628 }
2729 void ImuCallback (const void * msg, size_t ) const {
0 commit comments