Hi,
Also see this question. We're using a camera setup with multiple streams. One of the streams sends high resolution images. We use the camera's mjpeg video codec to compress the images. The ros pipeline does not use these images other than that it stores or uploads them as jpegs.
Instead of publishing the images as sensor_msgs.Image
messages, it makes more sense to publish them as sensor_msgs/CompressedImage
messages. In the depthai-ros library I couldn't find a way to create CompressedImage
messages though, so I try to add something to ImageConverter
myself (the C++ equivalent of the python code in the linked question, based on existing methods in ImageConverter
):
ImageMsgs::CompressedImage ImageConverter::toCompressedRosMsgRawPtr(std::shared_ptr<dai::ImgFrame> inData, const sensor_msgs::msg::CameraInfo & info)
{
std::chrono::_V2::steady_clock::time_point tstamp;
if (_getBaseDeviceTimestamp) {
if (_addExpOffset) {
tstamp = inData->getTimestampDevice(_expOffset);
} else {
tstamp = inData->getTimestampDevice();
}
} else if (_addExpOffset) {
tstamp = inData->getTimestamp(_expOffset);
} else {
tstamp = inData->getTimestamp();
}
StdMsgs::Header header;
header.frame_id = _frameName;
header.stamp = getFrameTime(_rosBaseTime, _steadyBaseTime, tstamp);
ImageMsgs::CompressedImage outImageMsg;
outImageMsg.header = header;
outImageMsg.format = "jpeg";
// Trying to copy compressed image data into outImageMsg.data, but these methods don't work:
// std::copy(inData->getData().begin(), inData->getData().end(), outImageMsg.data.begin());
// outImageMsg.data.insert(outImageMsg.data.begin(), inData->getFrame().begin(), inData->getFrame().end());
// outImageMsg.data.insert(outImageMsg.data.begin(), inData->getData().begin(), inData->getData().end());
return outImageMsg;
}
void ImageConverter::toCompressedRosMsg(std::shared_ptr<dai::ImgFrame> inData, std::deque<ImageMsgs::CompressedImage> & outImageMsgs)
{
auto outImageMsg = toCompressedRosMsgRawPtr(inData);
outImageMsgs.push_back(outImageMsg);
return;
}
CompressedImagePtr ImageConverter::toCompressedRosMsgPtr(std::shared_ptr<dai::ImgFrame> inData)
{
auto msg = toCompressedRosMsgRawPtr(inData);
CompressedImagePtr ptr = std::make_shared<ImageMsgs::CompressedImage>(msg);
return ptr;
}
But so far copying the data into the CompressedImage
message doesn't work. Either somewhere down the Ros pipeline OpenCV starts complaining that the message's data should not be empty. Or the camera node dies with an error message that gives no clue:
[ERROR] [camera_detector_node-2]: process has died [pid 67309, exit code -11, cmd '/home/oddbot/Documents/repos/vision-ros/install/camera_cpp/lib/camera_cpp/camera_detector_node --ros-args -r __node:=camera_node -r __ns:=/oddcore --params-file /home/oddbot/Documents/repos/vision-ros/install/vision_launch/share/vision_launch/config/oddcore_default_configs.yaml --params-file /home/oddbot/OddBotVisionLocal/config/oddcore_configs.yaml -r rgb/camera_info:=rgb/camera_info -r rgb/image_rect:=rgb/image_rect -r right/camera_info:=right/camera_info -r right/image:=right/image -r hires/camera_info:=hires/camera_info -r hires/image:=hires/image -r depth/camera_info:=depth/camera_info -r depth/image:=depth/image -r features:=features -r imu:=imu -r detections:=detections_plant'].
Does anyone know how I can copy the compressed image data into a CompressedImage
message?