From 2dd1858d2215695686c12d4c1d7b4241cce9d0c6 Mon Sep 17 00:00:00 2001 From: Angel Santamaria-Navarro <asantamaria@iri.upc.edu> Date: Fri, 23 Feb 2018 12:47:10 +0100 Subject: [PATCH] FIX: CV_bridge image encodings. cv_bridge does not support OpenCV formats, thus convertion is now done in the driver. --- src/mvbluefox3_camera_driver.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/mvbluefox3_camera_driver.cpp b/src/mvbluefox3_camera_driver.cpp index b79f8a2..eaedd59 100644 --- a/src/mvbluefox3_camera_driver.cpp +++ b/src/mvbluefox3_camera_driver.cpp @@ -302,10 +302,10 @@ void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &im encoding = "8UC1"; switch (bp) { - case 1: encoding = "8UC1"; break; + case 1: encoding = "mono8"; break; // FIX: Should be 8UC1 but changed because cv_bridge cannot convert formats case 2: encoding = "8UC2"; break; - case 3: encoding = "8UC3"; break; - case 4: encoding = "8UC4"; break; + case 3: encoding = "rgb8"; break; // FIX: Should be 8UC3 but changed because cv_bridge cannot convert formats + case 4: encoding = "rgba8"; break; // FIX: Should be 8UC4 but changed because cv_bridge cannot convert formats default: ROS_WARN("Invalid depth. Depth not implemented here."); break; } } @@ -314,7 +314,7 @@ void Mvbluefox3CameraDriver::GetROSImage(const int &ncam, sensor_msgs::Image &im encoding = "16UC1"; switch (bp) { - case 1: encoding = "16UC1"; break; + case 1: encoding = "mono16"; break; // FIX: Should be 16UC1 but changed because cv_bridge cannot convert formats case 2: encoding = "16UC2"; break; case 3: encoding = "16UC3"; break; case 4: encoding = "16UC4"; break; -- GitLab