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

Custom message with sensor_msgs/Image

asked 2015-04-12 04:28:40 -0500

mpkuse gravatar image

I have a custom .msg file MyImage.msg

sensor_msgs/Image im
float32 age
string name

I have configured the custom .msg fle as illustrated in link:CreatingMsgAndSrv

Further, I am trying to write a simple publisher with this msg.

#include <ros/ros.h>

#include <custom_msg/MyImage.h>
#include <image_transport/image_transport.h>


#include <opencv2/highgui/highgui.hpp>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>



int main( int argc, char ** argv )
{
    ros::init(argc, argv, "publish_custom");
    ros::NodeHandle nh;

    ros::Publisher pub2 = nh.advertise<custom_msg::MyImage>("custom_image", 2 );

    cv::Mat image = cv::imread( "Lenna.png", CV_LOAD_IMAGE_COLOR );
    sensor_msgs::ImagePtr im_msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();

    ros::Rate rate( 2 );

    while( ros::ok() )
    {
        ROS_INFO_STREAM_ONCE( "IN main loop");


        custom_msg::MyImage msg2;
        msg2.age=54.3;
        msg2.im = im_msg;
        msg2.name="Gena";

        pub2.publish(msg2);

        rate.sleep();
    }
}

This does not seem to compile with catkin_make. The error messages are -

/home/eeuser/ros_workspaces/HeloRosProject/src/custom_msg/publish.cpp: In function ‘int main(int, char**)’:
/home/eeuser/ros_workspaces/HeloRosProject/src/custom_msg/publish.cpp:40:19: error: no match for ‘operator=’ in ‘msg2.custom_msg::MyImage_<std::allocator<void> >::im = im_msg’
/home/eeuser/ros_workspaces/HeloRosProject/src/custom_msg/publish.cpp:40:19: note: candidate is:
/opt/ros/hydro/include/sensor_msgs/Image.h:56:8: note: sensor_msgs::Image_<std::allocator<void> >& sensor_msgs::Image_<std::allocator<void> >::operator=(const sensor_msgs::Image_<std::allocator<void> >&)
/opt/ros/hydro/include/sensor_msgs/Image.h:56:8: note:   no known conversion for argument 1 from ‘sensor_msgs::ImagePtr {aka boost::shared_ptr<sensor_msgs::Image_<std::allocator<void> > >}’ to ‘const sensor_msgs::Image_<std::allocator<void> >&’
make[2]: *** [custom_msg/CMakeFiles/publish.dir/publish.cpp.o] Error 1
make[1]: *** [custom_msg/CMakeFiles/publish.dir/all] Error 2
make: *** [all] Error 2
Invoking "make" failed

I can understand that msg2.im = im_msg; isn't correct. Please help me fix this.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2015-04-12 12:52:48 -0500

marguedas gravatar image

Hi,

It seems that you're using a pointer in one case (sensor_msgs::ImagePtr) and that your message is expecting a value (sensor_msgs/Image im). As explained at this line. no known conversion for argument 1 from ‘sensor_msgs::ImagePtr {aka boost::shared_ptr<sensor_msgs::image_<std::allocator<void> > >}’ to ‘const sensor_msgs::Image_<std::allocator<void> >&’
this means that you are providing a sensor_msgs::ImagePtr and the operator is expecting a const sensor_msgs::Image_ >&

So you need to change: msg2.im = im_msg; into msg2.im = *im_msg;

Hope this helps

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-04-12 04:28:40 -0500

Seen: 3,082 times

Last updated: Apr 12 '15