3434#include " usb_cam/usb_cam_node.hpp"
3535#include " usb_cam/utils.hpp"
3636
37+ const char BASE_TOPIC_NAME[] = " image_raw" ;
3738
3839namespace usb_cam
3940{
@@ -42,6 +43,12 @@ UsbCamNode::UsbCamNode(const rclcpp::NodeOptions & node_options)
4243: Node(" usb_cam" , node_options),
4344 m_camera (new usb_cam::UsbCam()),
4445 m_image_msg(new sensor_msgs::msg::Image()),
46+ m_compressed_img_msg(nullptr ),
47+ m_image_publisher(std::make_shared<image_transport::CameraPublisher>(
48+ image_transport::create_camera_publisher (this , BASE_TOPIC_NAME,
49+ rclcpp::QoS {100 }.get_rmw_qos_profile()))),
50+ m_compressed_image_publisher(nullptr ),
51+ m_compressed_cam_info_publisher(nullptr ),
4552 m_parameters(),
4653 m_camera_info_msg(new sensor_msgs::msg::CameraInfo()),
4754 m_service_capture(
@@ -54,10 +61,6 @@ UsbCamNode::UsbCamNode(const rclcpp::NodeOptions & node_options)
5461 std::placeholders::_2,
5562 std::placeholders::_3)))
5663{
57- m_image_publisher = image_transport::create_camera_publisher (
58- this , " image_raw" , rclcpp::QoS {100 }.get_rmw_qos_profile ()
59- );
60-
6164 // declare params
6265 this ->declare_parameter (" camera_name" , " default_cam" );
6366 this ->declare_parameter (" camera_info_url" , " " );
@@ -93,6 +96,7 @@ UsbCamNode::~UsbCamNode()
9396{
9497 RCLCPP_WARN (this ->get_logger (), " Shutting down" );
9598 m_image_msg.reset ();
99+ m_compressed_img_msg.reset ();
96100 m_camera_info_msg.reset ();
97101 m_camera_info.reset ();
98102 m_timer.reset ();
@@ -144,8 +148,8 @@ void UsbCamNode::init()
144148 if (available_devices.find (m_parameters.device_name ) == available_devices.end ()) {
145149 RCLCPP_ERROR_STREAM (
146150 this ->get_logger (),
147- " Device specified is not available or is not a vaild V4L2 device: `"
148- << m_parameters.device_name << " `"
151+ " Device specified is not available or is not a vaild V4L2 device: `" <<
152+ m_parameters.device_name << " `"
149153 );
150154 RCLCPP_INFO (this ->get_logger (), " Available V4L2 devices are:" );
151155 for (const auto & device : available_devices) {
@@ -156,6 +160,19 @@ void UsbCamNode::init()
156160 return ;
157161 }
158162
163+ // if pixel format is equal to 'mjpeg', i.e. raw mjpeg stream, initialize compressed image message
164+ // and publisher
165+ if (m_parameters.pixel_format_name == " mjpeg" ) {
166+ m_compressed_img_msg.reset (new sensor_msgs::msg::CompressedImage ());
167+ m_compressed_img_msg->header .frame_id = m_parameters.frame_id ;
168+ m_compressed_image_publisher =
169+ this ->create_publisher <sensor_msgs::msg::CompressedImage>(
170+ std::string (BASE_TOPIC_NAME) + " /compressed" , rclcpp::QoS (100 ));
171+ m_compressed_cam_info_publisher =
172+ this ->create_publisher <sensor_msgs::msg::CameraInfo>(
173+ " camera_info" , rclcpp::QoS (100 ));
174+ }
175+
159176 m_image_msg->header .frame_id = m_parameters.frame_id ;
160177 RCLCPP_INFO (
161178 this ->get_logger (), " Starting '%s' (%s) at %dx%d via %s (%s) at %i FPS" ,
@@ -361,7 +378,30 @@ bool UsbCamNode::take_and_send_image()
361378
362379 *m_camera_info_msg = m_camera_info->getCameraInfo ();
363380 m_camera_info_msg->header = m_image_msg->header ;
364- m_image_publisher.publish (*m_image_msg, *m_camera_info_msg);
381+ m_image_publisher->publish (*m_image_msg, *m_camera_info_msg);
382+ return true ;
383+ }
384+
385+ bool UsbCamNode::take_and_send_image_mjpeg ()
386+ {
387+ // Only resize if required
388+ if (sizeof (m_compressed_img_msg->data ) != m_camera->get_image_size_in_bytes ()) {
389+ m_compressed_img_msg->format = " jpeg" ;
390+ m_compressed_img_msg->data .resize (m_camera->get_image_size_in_bytes ());
391+ }
392+
393+ // grab the image, pass image msg buffer to fill
394+ m_camera->get_image (reinterpret_cast <char *>(&m_compressed_img_msg->data [0 ]));
395+
396+ auto stamp = m_camera->get_image_timestamp ();
397+ m_compressed_img_msg->header .stamp .sec = stamp.tv_sec ;
398+ m_compressed_img_msg->header .stamp .nanosec = stamp.tv_nsec ;
399+
400+ *m_camera_info_msg = m_camera_info->getCameraInfo ();
401+ m_camera_info_msg->header = m_compressed_img_msg->header ;
402+
403+ m_compressed_image_publisher->publish (*m_compressed_img_msg);
404+ m_compressed_cam_info_publisher->publish (*m_camera_info_msg);
365405 return true ;
366406}
367407
@@ -382,8 +422,12 @@ void UsbCamNode::update()
382422{
383423 if (m_camera->is_capturing ()) {
384424 // If the camera exposure longer higher than the framerate period
385- // then that caps the framerate
386- if (!take_and_send_image ()) {
425+ // then that caps the framerate.
426+ // auto t0 = now();
427+ bool isSuccessful = (m_parameters.pixel_format_name == " mjpeg" ) ?
428+ take_and_send_image_mjpeg () :
429+ take_and_send_image ();
430+ if (!isSuccessful) {
387431 RCLCPP_WARN_ONCE (this ->get_logger (), " USB camera did not respond in time." );
388432 }
389433 }
0 commit comments