ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Can't convert to image from /camera/image/compressed

asked 2019-01-16 06:14:44 -0500

ROStutorialLearner gravatar image

updated 2019-01-16 07:09:57 -0500

Hi, I've followed the tutorial at: http://wiki.ros.org/image_transport/T... and when trying to apply this knowledge to my own project I run into some issues.

OpenCV Error: The function/feature is not implemented (Unknown/unsupported array type) in getMat_, file /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp, line 1289
terminate called after throwing an instance of 'cv::Exception'
  what():  /build/opencv-L2vuMj/opencv-3.2.0+dfsg/modules/core/src/matrix.cpp:1289: error: (-213) Unknown/unsupported array type in function getMat_


Process finished with exit code 134 (interrupted by signal 6: SIGABRT)

However, when I use rqt_image_view I'm able to get an image:

image description

Code:

 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
 {
    try
    {
        cv::Mat image = cv::imdecode(cv::Mat(msg->data),1);//convert compressed image data to cv::Mat
       cv::imshow("view", image);
       cv::waitKey(10);
     }
     catch (cv_bridge::Exception& e)
     {
        ROS_ERROR("Could not convert to image!");
    }
 }


 int main(int argc, char **argv)

 {
    ros::init(argc, argv, "image_listener");
    ros::NodeHandle nh;
    cv::namedWindow("view");
    cv::startWindowThread();
    ros::Subscriber sub = nh.subscribe("/camera/image/compressed", 1, imageCallback);
    ros::spin();
    cv::destroyWindow("view");
    return 0;
 }

CMAKELISTS.TXT

cmake_minimum_required(VERSION 2.8.3)
project(our_robot)

## OpenCV required
find_package( OpenCV REQUIRED )

find_package(catkin REQUIRED COMPONENTS
  geometry_msgs
  roscpp
  sensor_msgs
  std_msgs
  image_transport
  cv_bridge
  std_msgs
)

catkin_package(
)

include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

add_executable(our_robot src/lf.cpp)
target_link_libraries(our_robot ${catkin_LIBRARIES})
target_link_libraries(our_robot ${OpenCV_LIBS} )
edit retag flag offensive close merge delete

Comments

1

You might want to add your CMakeLists.txt as well.

gvdhoorn gravatar image gvdhoorn  ( 2019-01-16 06:19:48 -0500 )edit
1

Added the cmakelists

ROStutorialLearner gravatar image ROStutorialLearner  ( 2019-01-16 06:43:34 -0500 )edit
1

Since you are already depending on cv_bridge, I don't believe you need to find_package(OpenCV ..) yourself any more.

You can probably remove the find_package(OpenCV ..) and the target_link_libraries(..) call.

gvdhoorn gravatar image gvdhoorn  ( 2019-01-16 07:04:38 -0500 )edit
1

Changing it to OpenCV 3 REQUIRED will make the program no longer compile because it can't find any OpenCV anymore, putting OpenCV 2 REQUIRED will compile, while it no longer produces an error, it now just shows a blank window. https://i.imgur.com/bzvU5hP.png Just like it did originally.

ROStutorialLearner gravatar image ROStutorialLearner  ( 2019-01-16 07:09:16 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2019-01-17 06:01:25 -0500

When I've worked with compressed image topics, I've never had to deal with the compressed data directly I've left that to the image_transport package. You can use the following code to setup a subscriber, this will work with the compressed topic if it is available, or with an uncompressed one if that's all that's available.

image_transport::ImageTransport it(n);
itSub = it.subscribe("topic_name", 1, imageCallbackFn, image_transport::TransportHints("compressed"));

Then your imageCallbackFn will be the same as a regular image callback because the decompression is being handled for you:

// Image callback
void imageCallbackFn(const sensor_msgs::ImageConstPtr& msg)
{
  cv_bridge::CvImagePtr cvImg = cv_bridge::toCvCopy(msg, "bgr8");
  cv::Mat myOpenCVImg = cvImg->image;
}

Hope this helps you get this working.

edit flag offensive delete link more
2

answered 2022-10-07 08:06:47 -0500

lucasw gravatar image

updated 2022-10-07 08:39:19 -0500

ImageTransport doesn't work for all purposes (for example a message filters sync subscriber between a CompressedImage and anything other than a CameraInfo), and likewise with a separate republish node for decompression, so if you want to do the decompression yourself call toCvCopy on it in a callback that subscribes directly to a CompressedImage:

void MyNode::compressedImageCallback(
    const sensor_msgs::CompressedImageConstPtr& image_msg)
{
  const std::string encoding = "bgr8";
  cv_bridge::CvImageConstPtr cv_ptr;
  try
  { 
    cv_ptr = cv_bridge::toCvCopy(image_msg, encoding);
  }
  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("cv_bridge exception: %s", e.what());
    return;
 }
...

The toCvCopy that converts the compressed image (cutting and paste code in to improve searchability here):

CvImagePtr toCvCopy(const sensor_msgs::CompressedImage& source, const std::string& encoding)
{
  // Construct matrix pointing to source data
  const cv::Mat_<uchar> in(1, source.data.size(), const_cast<uchar*>(&source.data[0]));
  // Loads as BGR or BGRA.
  const cv::Mat rgb_a = cv::imdecode(in, cv::IMREAD_UNCHANGED);

  if (encoding != enc::MONO16) {
    switch (rgb_a.channels())
    {
      case 4:
        return toCvCopyImpl(rgb_a, source.header, enc::BGRA8, encoding);
        break;
      case 3:
        return toCvCopyImpl(rgb_a, source.header, enc::BGR8, encoding);
        break;
      case 1:
        return toCvCopyImpl(rgb_a, source.header, enc::MONO8, encoding);
        break;
      default:
        return CvImagePtr();
    }
  }
  else {
    return toCvCopyImpl(rgb_a, source.header, enc::MONO16, encoding);
  }
}

https://github.com/ros-perception/vis...


There's another implementation here:

void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
                                            const Callback& user_cb)

{

  cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);

  // Copy message header
  cv_ptr->header = message->header;

  // Decode color/mono image
  try
  {
    cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_);

    // Assign image encoding string
    const size_t split_pos = message->format.find(';');
    if (split_pos==std::string::npos)
    {
      // Older version of compressed_image_transport does not signal image format
      switch (cv_ptr->image.channels())
      {
        case 1:
          cv_ptr->encoding = enc::MONO8;
          break;
        case 3:
          cv_ptr->encoding = enc::BGR8;
          break;
        default:
          ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels());
          break;
      }
    } else
    {
      std::string image_encoding = message->format.substr(0, split_pos);

      cv_ptr->encoding = image_encoding;

      if ( enc::isColor(image_encoding))
      {
        std::string compressed_encoding = message->format.substr(split_pos);
        bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos);

        // Revert color transformation
        if (compressed_bgr_image)
        {
          // if necessary convert colors from bgr to rgb
          if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);

          if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);

          if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
        } else
        {
          // if necessary convert colors from rgb to bgr
          if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);

          if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);

          if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
            cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
        }
      }
    }
  }
  catch (cv::Exception& e)
  {
    ROS_ERROR("%s", e.what());
  }

  size_t rows = cv_ptr->image.rows;
  size_t cols = cv_ptr->image.cols;

  if ((rows > 0) && (cols > 0))
    // Publish message to user callback
    user_cb(cv_ptr->toImageMsg());
}

https://github.com/ros-perception/ima...

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-01-16 06:14:44 -0500

Seen: 2,560 times

Last updated: Oct 07 '22