@@ -67,7 +67,9 @@ class MetadataExportFiles : public rclcpp::Node {
6767 }
6868
6969 void load_parameters () {
70- std::ifstream file (" install/orbbec_camera/share/orbbec_camera/config/metadataexport/metadata_export_params.json" );
70+ std::ifstream file (
71+ " install/orbbec_camera/share/orbbec_camera/config/metadataexport/"
72+ " metadata_export_params.json" );
7173 if (!file.is_open ()) {
7274 RCLCPP_ERROR (this ->get_logger (), " Failed to open JSON file." );
7375 return ;
@@ -106,8 +108,7 @@ class MetadataExportFiles : public rclcpp::Node {
106108
107109 left_ir_sync_ = std::make_shared<message_filters::Synchronizer<MySyncPolicy>>(
108110 MySyncPolicy (10 ), *left_ir_image_sub_, *left_ir_metadata_sub_);
109- left_ir_sync_->setMaxIntervalDuration (
110- rclcpp::Duration::from_nanoseconds (100000000LL )); // 100 ms
111+ left_ir_sync_->setMaxIntervalDuration (rclcpp::Duration (0 , 100 * 1000000 )); // 100 ms
111112
112113 left_ir_sync_->registerCallback (
113114 std::bind (&MetadataExportFiles::left_ir_metadata_sync_callback, this , _1, _2));
@@ -120,8 +121,7 @@ class MetadataExportFiles : public rclcpp::Node {
120121
121122 right_ir_sync_ = std::make_shared<message_filters::Synchronizer<MySyncPolicy>>(
122123 MySyncPolicy (10 ), *right_ir_image_sub_, *right_ir_metadata_sub_);
123- right_ir_sync_->setMaxIntervalDuration (
124- rclcpp::Duration::from_nanoseconds (100000000LL )); // 100 ms
124+ right_ir_sync_->setMaxIntervalDuration (rclcpp::Duration (0 , 100 * 1000000 )); // 100 ms
125125
126126 right_ir_sync_->registerCallback (
127127 std::bind (&MetadataExportFiles::right_ir_metadata_sync_callback, this , _1, _2));
@@ -134,7 +134,7 @@ class MetadataExportFiles : public rclcpp::Node {
134134
135135 depth_sync_ = std::make_shared<message_filters::Synchronizer<MySyncPolicy>>(
136136 MySyncPolicy (10 ), *depth_image_sub_, *depth_metadata_sub_);
137- depth_sync_->setMaxIntervalDuration (rclcpp::Duration::from_nanoseconds ( 100000000LL )); // 100 ms
137+ depth_sync_->setMaxIntervalDuration (rclcpp::Duration ( 0 , 100 * 1000000 )); // 100 ms
138138
139139 depth_sync_->registerCallback (
140140 std::bind (&MetadataExportFiles::depth_metadata_sync_callback, this , _1, _2));
@@ -147,7 +147,7 @@ class MetadataExportFiles : public rclcpp::Node {
147147
148148 color_sync_ = std::make_shared<message_filters::Synchronizer<MySyncPolicy>>(
149149 MySyncPolicy (10 ), *color_image_sub_, *color_metadata_sub_);
150- color_sync_->setMaxIntervalDuration (rclcpp::Duration::from_nanoseconds ( 100000000LL )); // 100 ms
150+ color_sync_->setMaxIntervalDuration (rclcpp::Duration ( 0 , 100 * 1000000 )); // 100 ms
151151
152152 color_sync_->registerCallback (
153153 std::bind (&MetadataExportFiles::color_metadata_sync_callback, this , _1, _2));
@@ -380,9 +380,10 @@ class MetadataExportFiles : public rclcpp::Node {
380380 }
381381
382382 std::ostringstream ss;
383- ss << serial_path << " /" << std::to_string (frame_index) << " _" << " 0000" << " _"
384- << camera_timestamp_us << " _" << timestamp_us.str () << " _" << prefix << " _" << resolution
385- << " .png" ;
383+ ss << serial_path << " /" << std::to_string (frame_index) << " _"
384+ << " 0000"
385+ << " _" << camera_timestamp_us << " _" << timestamp_us.str () << " _" << prefix << " _"
386+ << resolution << " .png" ;
386387 cv::imwrite (ss.str (), cv_ptr->image );
387388 }
388389 void save_metadata_to_file (const ImageMetadata &metadata, const std::string &prefix) {
0 commit comments