Skip to content

Commit aa11493

Browse files
authored
Merge pull request #270 from boitumeloruf/raw-mjpeg-stream
Publish raw mjpeg stream directly via compressed image topic
2 parents bbc47d7 + 7ad056f commit aa11493

File tree

7 files changed

+231
-11
lines changed

7 files changed

+231
-11
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@ endif()
3030
find_package(OpenCV REQUIRED)
3131

3232
find_package(PkgConfig REQUIRED)
33+
pkg_check_modules(avcodec REQUIRED libavcodec)
3334
pkg_check_modules(avutil REQUIRED libavutil)
3435
pkg_check_modules(swscale REQUIRED libswscale)
3536

include/usb_cam/formats/av_pixel_format_helper.hpp

Lines changed: 148 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ extern "C" {
3838
#include "libavutil/pixfmt.h"
3939
}
4040

41+
#include "usb_cam/constants.hpp"
42+
4143
#define stringify(name) #name
4244

4345

@@ -958,6 +960,152 @@ inline AVPixelFormat get_av_pixel_format_from_string(const std::string & str)
958960
return STR_2_AVPIXFMT.find(fullFmtStr)->second;
959961
}
960962

963+
/// @brief Get ROS PixelFormat from AVPixelFormat.
964+
/// @param avPixelFormat AVPixelFormat
965+
/// @return String specifying the ROS pixel format.
966+
inline std::string get_ros_pixel_format_from_av_format(const AVPixelFormat & avPixelFormat)
967+
{
968+
std::string ros_format = "";
969+
970+
switch (avPixelFormat) {
971+
default:
972+
{
973+
ros_format = usb_cam::constants::UNKNOWN;
974+
}
975+
break;
976+
977+
case AVPixelFormat::AV_PIX_FMT_RGB24:
978+
{
979+
ros_format = usb_cam::constants::RGB8;
980+
}
981+
break;
982+
983+
case AVPixelFormat::AV_PIX_FMT_RGBA:
984+
{
985+
ros_format = usb_cam::constants::RGBA8;
986+
}
987+
break;
988+
989+
case AVPixelFormat::AV_PIX_FMT_BGR24:
990+
{
991+
ros_format = usb_cam::constants::BGR8;
992+
}
993+
break;
994+
995+
case AVPixelFormat::AV_PIX_FMT_BGRA:
996+
{
997+
ros_format = usb_cam::constants::BGRA8;
998+
}
999+
break;
1000+
1001+
case AVPixelFormat::AV_PIX_FMT_GRAY8:
1002+
{
1003+
ros_format = usb_cam::constants::MONO8;
1004+
}
1005+
break;
1006+
1007+
case AVPixelFormat::AV_PIX_FMT_GRAY16BE:
1008+
{
1009+
ros_format = usb_cam::constants::MONO16;
1010+
}
1011+
break;
1012+
1013+
case AVPixelFormat::AV_PIX_FMT_YUV422P:
1014+
{
1015+
ros_format = usb_cam::constants::YUV422;
1016+
}
1017+
break;
1018+
1019+
case AVPixelFormat::AV_PIX_FMT_YUV420P:
1020+
{
1021+
ros_format = usb_cam::constants::NV21;
1022+
}
1023+
break;
1024+
1025+
case AVPixelFormat::AV_PIX_FMT_YUV444P:
1026+
{
1027+
ros_format = usb_cam::constants::NV24;
1028+
}
1029+
break;
1030+
}
1031+
1032+
return ros_format;
1033+
}
1034+
1035+
/// @brief Get the number of channels from AVPixelFormat.
1036+
/// @param avPixelFormat AVPixelFormat
1037+
/// @return Number of channels as uint8
1038+
inline uint8_t get_channels_from_av_format(const AVPixelFormat & avPixelFormat)
1039+
{
1040+
uint8_t channels = 1;
1041+
1042+
switch (avPixelFormat) {
1043+
default:
1044+
case AVPixelFormat::AV_PIX_FMT_GRAY8:
1045+
case AVPixelFormat::AV_PIX_FMT_GRAY16BE:
1046+
{
1047+
channels = 1;
1048+
}
1049+
break;
1050+
1051+
case AVPixelFormat::AV_PIX_FMT_YUV422P:
1052+
case AVPixelFormat::AV_PIX_FMT_YUV420P:
1053+
case AVPixelFormat::AV_PIX_FMT_YUV444P:
1054+
{
1055+
channels = 2;
1056+
}
1057+
break;
1058+
1059+
case AVPixelFormat::AV_PIX_FMT_RGB24:
1060+
case AVPixelFormat::AV_PIX_FMT_BGR24:
1061+
{
1062+
channels = 3;
1063+
}
1064+
break;
1065+
1066+
case AVPixelFormat::AV_PIX_FMT_RGBA:
1067+
case AVPixelFormat::AV_PIX_FMT_BGRA:
1068+
{
1069+
channels = 4;
1070+
}
1071+
break;
1072+
}
1073+
1074+
return channels;
1075+
}
1076+
1077+
/// @brief Get the pixel bit depth from AVPixelFormat.
1078+
/// @param avPixelFormat AVPixelFormat
1079+
/// @return Bit depth as uint8
1080+
inline uint8_t get_bit_depth_from_av_format(const AVPixelFormat & avPixelFormat)
1081+
{
1082+
uint8_t bit_depth = 8;
1083+
1084+
switch (avPixelFormat) {
1085+
default:
1086+
case AVPixelFormat::AV_PIX_FMT_GRAY8:
1087+
case AVPixelFormat::AV_PIX_FMT_RGB24:
1088+
case AVPixelFormat::AV_PIX_FMT_BGR24:
1089+
case AVPixelFormat::AV_PIX_FMT_RGBA:
1090+
case AVPixelFormat::AV_PIX_FMT_BGRA:
1091+
case AVPixelFormat::AV_PIX_FMT_YUV422P:
1092+
case AVPixelFormat::AV_PIX_FMT_YUV420P:
1093+
case AVPixelFormat::AV_PIX_FMT_YUV444P:
1094+
{
1095+
bit_depth = 8;
1096+
}
1097+
break;
1098+
1099+
case AVPixelFormat::AV_PIX_FMT_GRAY16BE:
1100+
{
1101+
bit_depth = 16;
1102+
}
1103+
break;
1104+
}
1105+
1106+
return bit_depth;
1107+
}
1108+
9611109
} // namespace formats
9621110
} // namespace usb_cam
9631111

include/usb_cam/formats/mjpeg.hpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,13 +52,29 @@ extern "C" {
5252
#include "usb_cam/usb_cam.hpp"
5353
#include "usb_cam/formats/pixel_format_base.hpp"
5454
#include "usb_cam/formats/utils.hpp"
55+
#include "usb_cam/formats/av_pixel_format_helper.hpp"
5556

5657

5758
namespace usb_cam
5859
{
5960
namespace formats
6061
{
6162

63+
class RAW_MJPEG : public pixel_format_base
64+
{
65+
public:
66+
explicit RAW_MJPEG(const AVPixelFormat & avDeviceFormat)
67+
: pixel_format_base(
68+
"raw_mjpeg",
69+
V4L2_PIX_FMT_MJPEG,
70+
get_ros_pixel_format_from_av_format(avDeviceFormat),
71+
get_channels_from_av_format(avDeviceFormat),
72+
get_bit_depth_from_av_format(avDeviceFormat),
73+
false)
74+
{
75+
}
76+
};
77+
6278
class MJPEG2RGB : public pixel_format_base
6379
{
6480
public:

include/usb_cam/usb_cam.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -288,6 +288,7 @@ class UsbCam
288288
using usb_cam::formats::MONO8;
289289
using usb_cam::formats::MONO16;
290290
using usb_cam::formats::Y102MONO8;
291+
using usb_cam::formats::RAW_MJPEG;
291292
using usb_cam::formats::MJPEG2RGB;
292293
using usb_cam::formats::M4202RGB;
293294

@@ -303,6 +304,9 @@ class UsbCam
303304
} else if (parameters.pixel_format_name == "uyvy2rgb") {
304305
// number of pixels required for conversion method
305306
m_image.pixel_format = std::make_shared<UYVY2RGB>(m_image.number_of_pixels);
307+
} else if (parameters.pixel_format_name == "mjpeg") {
308+
m_image.pixel_format = std::make_shared<RAW_MJPEG>(
309+
formats::get_av_pixel_format_from_string(parameters.av_device_format));
306310
} else if (parameters.pixel_format_name == "mjpeg2rgb") {
307311
m_image.pixel_format = std::make_shared<MJPEG2RGB>(
308312
m_image.width, m_image.height,

include/usb_cam/usb_cam_node.hpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include "image_transport/image_transport.hpp"
4040
#include "rclcpp/rclcpp.hpp"
4141
#include "sensor_msgs/msg/image.hpp"
42+
#include "sensor_msgs/msg/compressed_image.hpp"
4243
#include "std_srvs/srv/set_bool.hpp"
4344

4445
#include "usb_cam/usb_cam.hpp"
@@ -66,6 +67,7 @@ class UsbCamNode : public rclcpp::Node
6667
void set_v4l2_params();
6768
void update();
6869
bool take_and_send_image();
70+
bool take_and_send_image_mjpeg();
6971

7072
rcl_interfaces::msg::SetParametersResult parameters_callback(
7173
const std::vector<rclcpp::Parameter> & parameters);
@@ -77,8 +79,11 @@ class UsbCamNode : public rclcpp::Node
7779

7880
UsbCam * m_camera;
7981

80-
sensor_msgs::msg::Image::SharedPtr m_image_msg;
81-
image_transport::CameraPublisher m_image_publisher;
82+
sensor_msgs::msg::Image::UniquePtr m_image_msg;
83+
sensor_msgs::msg::CompressedImage::UniquePtr m_compressed_img_msg;
84+
std::shared_ptr<image_transport::CameraPublisher> m_image_publisher;
85+
rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr m_compressed_image_publisher;
86+
rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr m_compressed_cam_info_publisher;
8287

8388
parameters_t m_parameters;
8489

include/usb_cam/utils.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ extern "C" {
3535

3636
#include <sys/ioctl.h>
3737
#include <sys/time.h>
38+
#include <unistd.h> // for access
3839
#include <cmath>
3940
#include <ctime>
4041
#include <cstring>
@@ -47,6 +48,7 @@ extern "C" {
4748
#include "usb_cam/constants.hpp"
4849
#include "usb_cam/formats/pixel_format_base.hpp"
4950

51+
5052
namespace usb_cam
5153
{
5254
namespace utils

src/ros2/usb_cam_node.cpp

Lines changed: 53 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#include "usb_cam/usb_cam_node.hpp"
3535
#include "usb_cam/utils.hpp"
3636

37+
const char BASE_TOPIC_NAME[] = "image_raw";
3738

3839
namespace 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

Comments
 (0)