|
47 | 47 | #include <rclcpp/publisher.hpp> |
48 | 48 | #include <rclcpp/time.hpp> |
49 | 49 | #include <rclcpp_components/register_node_macro.hpp> |
| 50 | +#include <regex> |
50 | 51 | #include <sensor_msgs/image_encodings.hpp> |
51 | 52 | #include <sensor_msgs/msg/camera_info.hpp> |
52 | 53 | #include <sensor_msgs/msg/compressed_image.hpp> |
@@ -150,6 +151,31 @@ get_role(const std::string &role) |
150 | 151 | } |
151 | 152 | } |
152 | 153 |
|
| 154 | +libcamera::Size |
| 155 | +get_sensor_format(const std::string &format_str) |
| 156 | +{ |
| 157 | + if (format_str.empty()) { |
| 158 | + return {}; |
| 159 | + } |
| 160 | + |
| 161 | + const std::regex pattern(R"((\d{1,19}):(\d{1,19}))"); |
| 162 | + std::smatch match; |
| 163 | + |
| 164 | + if (std::regex_match(format_str, match, pattern)) { |
| 165 | + const unsigned long width = std::stoul(match[1].str()); |
| 166 | + const unsigned long height = std::stoul(match[2].str()); |
| 167 | + |
| 168 | + // Check for overflow |
| 169 | + if (width > std::numeric_limits<uint32_t>::max() || height > std::numeric_limits<uint32_t>::max()) { |
| 170 | + throw std::runtime_error("Width or height exceeds maximum value of " + std::to_string(std::numeric_limits<uint32_t>::max())); |
| 171 | + } |
| 172 | + |
| 173 | + return libcamera::Size {static_cast<uint32_t>(width), static_cast<uint32_t>(height)}; |
| 174 | + } |
| 175 | + else { |
| 176 | + throw std::runtime_error("Invalid size format! Expected [width]:[height] but got " + format_str); |
| 177 | + } |
| 178 | +} |
153 | 179 |
|
154 | 180 | // The following function "compressImageMsg" is adapted from "CvImage::toCompressedImageMsg" |
155 | 181 | // (https://github.com/ros-perception/vision_opencv/blob/066793a23e5d06d76c78ca3d69824a501c3554fd/cv_bridge/src/cv_bridge.cpp#L512-L535) |
@@ -221,6 +247,13 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) |
221 | 247 | const uint32_t h = declare_parameter<int64_t>("height", {}, param_descr_ro); |
222 | 248 | const libcamera::Size size {w, h}; |
223 | 249 |
|
| 250 | + // Raw format dimensions |
| 251 | + rcl_interfaces::msg::ParameterDescriptor param_descr_sensor_mode; |
| 252 | + param_descr_sensor_mode.description = "raw mode of the sensor"; |
| 253 | + param_descr_sensor_mode.additional_constraints = "string in format [width]:[height]"; |
| 254 | + param_descr_sensor_mode.read_only = true; |
| 255 | + const libcamera::Size sensor_size = get_sensor_format(declare_parameter<std::string>("sensor_mode", {}, param_descr_sensor_mode)); |
| 256 | + |
224 | 257 | // camera info file url |
225 | 258 | rcl_interfaces::msg::ParameterDescriptor param_descr_camera_info_url; |
226 | 259 | param_descr_camera_info_url.description = "camera calibration info file url"; |
@@ -299,14 +332,20 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) |
299 | 332 | if (camera->acquire()) |
300 | 333 | throw std::runtime_error("failed to acquire camera"); |
301 | 334 |
|
| 335 | + std::vector<libcamera::StreamRole> roles {role}; |
| 336 | + |
| 337 | + // Add the RAW role if the sensor_size is defined |
| 338 | + if (!sensor_size.isNull() && role != libcamera::StreamRole::Raw) { |
| 339 | + roles.push_back(libcamera::StreamRole::Raw); |
| 340 | + } |
| 341 | + |
302 | 342 | // configure camera stream |
303 | 343 | std::unique_ptr<libcamera::CameraConfiguration> cfg = |
304 | | - camera->generateConfiguration({role}); |
| 344 | + camera->generateConfiguration(roles); |
305 | 345 |
|
306 | | - if (!cfg) |
307 | | - throw std::runtime_error("failed to generate configuration"); |
| 346 | + if (!cfg || cfg->size() != roles.size()) |
| 347 | + throw std::runtime_error("failed to generate configuration for all roles"); |
308 | 348 |
|
309 | | - assert(cfg->size() == 1); |
310 | 349 | libcamera::StreamConfiguration &scfg = cfg->at(0); |
311 | 350 |
|
312 | 351 | // list all camera formats, including those not supported by the ROS message |
@@ -357,6 +396,12 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) |
357 | 396 | scfg.size = size; |
358 | 397 | } |
359 | 398 |
|
| 399 | + if (!sensor_size.isNull() && role != libcamera::StreamRole::Raw) { |
| 400 | + libcamera::StreamConfiguration &modecfg = cfg->at(1); |
| 401 | + modecfg.size = sensor_size; |
| 402 | + RCLCPP_INFO_STREAM(get_logger(), "Sensor mode configuration: " << modecfg.toString()); |
| 403 | + } |
| 404 | + |
360 | 405 | // store selected stream configuration |
361 | 406 | const libcamera::StreamConfiguration selected_scfg = scfg; |
362 | 407 |
|
@@ -392,6 +437,8 @@ CameraNode::CameraNode(const rclcpp::NodeOptions &options) |
392 | 437 | const std::optional<std::string> model = props.get(libcamera::properties::Model); |
393 | 438 | if (model) |
394 | 439 | cname = model.value() + '_' + cname; |
| 440 | + if (!sensor_size.isNull() && role != libcamera::StreamRole::Raw) |
| 441 | + cname = cname + '_' + cfg->at(1).toString(); |
395 | 442 |
|
396 | 443 | // clean camera name of non-alphanumeric characters |
397 | 444 | cname.erase( |
|
0 commit comments