Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <fstream>
#include <iomanip>
#include <sstream>
#include <stdexcept>
#include <string>
#include <vector>

Expand Down Expand Up @@ -55,10 +56,9 @@ class CompressedImageHandler : public BaseHandler
} else if (compressed_img.format.find("png") != std::string::npos) {
extension = ".png";
} else {
RCLCPP_WARN(
logger_, "Unknown compressed image format: %s. Defaulting to '.jpg'",
compressed_img.format.c_str());
extension = ".jpg"; // Default to JPEG if unknown
// Only support .jpg and .png formats
throw std::invalid_argument(
"Unsupported compressed image format found: " + compressed_img.format);
}

// Create a timestamped filename and save compressed image directly
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,9 @@ class ImageHandler : public BaseHandler
{
// Validate or set default encoding if not provided
if (encoding.empty()) {
RCLCPP_WARN(logger, "No encoding provided. Defaulting to 'rgb8'.");
encoding_ = "rgb8"; // Default to rgb8 if encoding is not provided
RCLCPP_WARN(logger, "No encoding provided. Defaulting to 'bgr8'.");
// Default to bgr8 if encoding is not provided
encoding_ = "bgr8";
} else {
encoding_ = encoding;
}
Expand Down Expand Up @@ -90,32 +91,14 @@ class ImageHandler : public BaseHandler
try {
cv_ptr = cv_bridge::toCvCopy(img_msg, encoding_);
} catch (const cv_bridge::Exception & e) {
RCLCPP_WARN(logger_, "CV Bridge exception: %s. Using default encoding 'rgb8'.", e.what());

// Attempt to fallback to the default 'rgb8' encoding
try {
cv_ptr = cv_bridge::toCvCopy(img_msg, "rgb8");
encoding_ = "rgb8"; // Update to fallback encoding
} catch (const cv_bridge::Exception & e2) {
RCLCPP_WARN(logger_, "Fallback to 'rgb8' failed: %s", e2.what());
return false;
}
throw std::runtime_error(
"CV Bridge failed to convert to the requested encoding: " + encoding_);
}

// Apply color conversion based on encoding
// cv_bridge can correctly convert 'bayer_rggb8' or 'bayer_bggr8' to BGR8 or Mono8.
// If "rgb8" is needed, an extra conversion is required since cv_bridge doesn't handle it
// directly
if (encoding_ == "rgb8") {
// Convert from RGB to BGR for saving with OpenCV (OpenCV uses BGR)
cv::cvtColor(cv_ptr->image, cv_ptr->image, cv::COLOR_RGB2BGR);
} else if (encoding_ == "bgr8") {
// No conversion needed, OpenCV already uses BGR format
RCLCPP_DEBUG(logger_, "Image is already in 'bgr8', no conversion applied.");
} else if (encoding_ == "mono8" || encoding_ == "mono16") {
// Grayscale images (mono8 or mono16), no color conversion needed
RCLCPP_DEBUG(
logger_, "Image is grayscale (%s), no color conversion applied.", encoding_.c_str());
} else {
RCLCPP_WARN(
logger_, "Unsupported image encoding '%s'. Skipping color conversion.", encoding_.c_str());
}

// Write the image to disk
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <filesystem>
#include <iomanip>
#include <sstream>
#include <stdexcept>
#include <string>
#include <vector>

Expand Down Expand Up @@ -71,15 +72,13 @@ class PointCloudHandler : public BaseHandler
pc2_msg.fields.begin(), pc2_msg.fields.end(),
[](const auto & field) { return field.name == "intensity"; });

// Create the appropriate point cloud, convert the ROS message, and save it
// Create the point cloud, convert the ROS message, and save it
if (has_intensity) {
pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>);
pcl::fromROSMsg(pc2_msg, *cloud);
return save_pointcloud_to_file<pcl::PointXYZI>(cloud, data_meta.data_path);
} else {
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(pc2_msg, *cloud);
return save_pointcloud_to_file<pcl::PointXYZ>(cloud, data_meta.data_path);
throw std::invalid_argument("The pointcloud message should have an 'intensity' field!");
}
}

Expand Down
20 changes: 12 additions & 8 deletions ros2_bag_exporter/src/bag_exporter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,9 @@ void BagExporter::export_bag()
// Construct rclcpp::SerializedMessage from serialized_data
rclcpp::SerializedMessage ser_msg(*serialized_msg->serialized_data);
handlers_["/tf_static"].handler->process_message(ser_msg, global_id);
handlers_["/tf_static"].handler->save_msg_to_file(0);
if (handlers_["/tf_static"].handler->save_msg_to_file(0)) {
throw std::runtime_error("Failed to save tf_static message to file");
}
tf_extracted_ = true;
}

Expand All @@ -247,7 +249,9 @@ void BagExporter::export_bag()
rclcpp::SerializedMessage ser_msg(*serialized_msg->serialized_data);

cam_info_handler.handler->process_message(ser_msg, global_id);
cam_info_handler.handler->save_msg_to_file(0);
if (!cam_info_handler.handler->save_msg_to_file(0)) {
throw std::runtime_error("Failed to save camera info message to file");
}

// Increase counter
camera_info_extracted_n += 1;
Expand Down Expand Up @@ -331,9 +335,9 @@ void BagExporter::create_metadata_file()

// Save this pointcloud
if (!main_sensor_handler->save_msg_to_file(idx)) {
RCLCPP_WARN(
this->get_logger(), "Unable to save pointcloud msg as file, global_id: %li",
main_data_meta.global_id);
throw std::runtime_error(
"Unable to save pointcloud msg as file, global_id: " +
std::to_string(main_data_meta.global_id));
}

// Save file name relative to rosbag_base_name_
Expand Down Expand Up @@ -370,9 +374,9 @@ void BagExporter::create_metadata_file()

// Save this image
if (!curr_cam_handler->save_msg_to_file(closest_time_index)) {
RCLCPP_WARN(
this->get_logger(), "Unable to save image msg as file, global_id: %li",
main_data_meta.global_id);
throw std::runtime_error(
"Unable to save image msg as file, global_id: " +
std::to_string(main_data_meta.global_id));
}

// Save file name relative to rosbag_base_name_
Expand Down