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

How would I publish a 2D float Array through a ROS message?

asked 2017-02-22 08:05:55 -0500

sharan100 gravatar image

updated 2017-03-07 08:00:09 -0500

I am currently working on a circle detection app. Using OpenCV, I get a std::vector<std::vector<float>> named v. Now I want to send this to a different executable node. So I made a simple Circles.msg which is:

float32[][] circles

However, I get a bunch of errors, mostly which are:

'const class std::vector<std::vector<float> >' has no member named '__getMD5Sum'

From the line:

circle_pub_.publish(v);

which I get from:

ros::Publisher circle_pub_;
circle_pub_ = node.advertise("/circles", 1);

So therefore, I don't know how to approach this problem.

I also do not understand how to subscribe to this topic. Currently I got:

circles_in = node.subscribe("/circles", 1, organizer_callback);
void organizer_callback( const std::vector< std::vector<float> >& circles) {
    ....
}

Is this okay? Please let me know if you know any more information!


The Code

Here is the most important parts of my program as of now:

class ImageConverter {
  ros::NodeHandle nh_;
  image_transport::ImageTransport it_;
  image_transport::Subscriber image_sub_;
  image_transport::Publisher image_pub_;
  ros::Publisher circle_pub_;

public:
  ImageConverter()
    : it_(nh_)
  {

        // Subscribe to the Bottom Raw Image
        image_sub_ = it_.subscribe("/ardrone/bottom/image_raw", 1, 
                &ImageConverter::imageCb, this);


        // Advertisng the Circles being detected from this 
                circle_pub_ =  nh_.advertise<zlab_drone::Circles>("/circles", 1);

  }

  void imageCb(const sensor_msgs::ImageConstPtr& msg)
  {
       // Find the circles from a particular video  
       cv::vector<cv::Vec3f> circles; 
       cv::HoughCircles(img_bin, circles, CV_HOUGH_GRADIENT, 1, 70, 140, 15, 
                    20, 400);


       std::vector<zlab_drone::Circle> v;

       for(int i = 0; i < circles.size(); ++i) {
           const cv::Vec3f& c = circles[i];
           v[i][0] = c[0];
           v[i][1] = c[1];
           v[i][2] = c[2];
       } 

       circle_pub_.publish(v);

    }
};

Subscriber

Here's the code from my subscriber:

// Gathering Data from the messages
for (std::vector<zlab_drone::Circles>::const_iterator gp = 
    msg->circles.begin(); gp!= msg->circles.end(), ++gp) {
    for (std::vector<float>::const_iterator dp = 
        gp->circle.begin(); dp != gp->circle.end(); ++dp) {
        circles[gp][dp] = gp->circle(dp); 
    }
}
edit retag flag offensive close merge delete

Comments

Just a general comment: you can't publish/subscribe arbitrary datatypes, as you are trying to do, only messages (ie: specially crafted containers that are declaratively described in .msg files). @suforeman's answer shows how you could nest two such msgs to get a 2d array.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-23 01:05:18 -0500 )edit

@gvdhoorn Makes sense. However, when I implemented @suforeman's answer, I retained all the same errors.

sharan100 gravatar image sharan100  ( 2017-02-23 01:20:25 -0500 )edit
1

Well without seeing what you did exactly, it's hard to know what could be wrong, but I know from experience that what @suforeman suggests works.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-23 01:52:12 -0500 )edit

@gvdhoorn I have added the most relavant bits of code in the question now. I have also implemented what @suforeman has implemented.

sharan100 gravatar image sharan100  ( 2017-02-23 06:03:27 -0500 )edit

Your latest edit suggests you're still not using message definitions / classes, but std::vector<std::vector<float>>.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-24 00:43:00 -0500 )edit

@gvdhoorn I still haven't understood how the publisher would be? I have edited the code to the most correct versions right now.

sharan100 gravatar image sharan100  ( 2017-03-07 07:08:41 -0500 )edit

You still appear to be trying to defining your topic subscriber without using your message definition. Compare your callback with the one in my answer's example. Try to get your subscriber working first. You can test your subscriber from the command line using rostopic.

suforeman gravatar image suforeman  ( 2017-03-07 07:31:33 -0500 )edit

@ suforeman I have made the subscriber work exactly as you specified within your answer.

sharan100 gravatar image sharan100  ( 2017-03-07 08:00:45 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2017-02-22 08:47:40 -0500

BrettHemes gravatar image

You could use the method answered previously here or use a single array in conjunction with a step value (length of the rows) as is commonly done for 2D image data via something like sensor_msgs/Image.

For example (assuming row-major) element circles[i][j] would be at data[i*step + j]

edit flag offensive delete link more

Comments

I assume I wouldn't be getting any of the errors from above if I implement it this way, but I wanted a more object oriented solution to this problem. If I can't find anything by the end of today, I will have to accept and implement your answer.

sharan100 gravatar image sharan100  ( 2017-02-22 23:31:49 -0500 )edit
1

answered 2017-02-22 12:50:13 -0500

updated 2017-02-24 09:04:24 -0500

I've had my best success by decomposing the message definition.

Working example:

Messages:

Group.msg:
    float32[] data
Groups.msg:
    Group[] group

CMakeLists.txt

cmake_minimum_required(VERSION 2.8.3)
project(groups)

find_package(catkin REQUIRED COMPONENTS roscpp std_msgs message_generation)

add_message_files(DIRECTORY msg FILES Group.msg Groups.msg)

generate_messages(DEPENDENCIES std_msgs)

catkin_package(CATKIN_DEPENDS roscpp std_msgs message_runtime)

include_directories(include  ${catkin_INCLUDE_DIRS})
link_directories(${catkin_LIBRARY_DIRS})


add_executable(groups src/groups.cpp)
target_link_libraries(groups ${catkin_LIBRARIES})
add_dependencies(groups groups_generate_messages_cpp)

install(TARGETS groups
    RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 
        LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 
        ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 
)
install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h" )
install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch )

Code:

#include <stdio.h>
#include <stdlib.h>
#include <string.h>

#include <ros/ros.h>
#include <ros/console.h>                                                                                                                                                                           

// messages
#include "groups/Group.h"
#include "groups/Groups.h"

void echo_groups (const groups::Groups::ConstPtr& msg)
{
    for(std::vector<groups::Group>::const_iterator gp = msg->group.begin(); gp != msg->group.end(); ++gp) {
        for (std::vector<float>::const_iterator dp = gp->data.begin(); dp != gp->data.end(); ++dp)
            std::cout << *dp << ' ';
        std::cout << '\n';
    }
}

int main (int argc, char **argv)
{
    ros::init (argc, argv, "groups");
    ros::NodeHandle n;
    ros::Subscriber groups_sub = n.subscribe ("echo_groups", 8, echo_groups);
    ros::spin();

  return 0;
}

Test:

rostopic pub -1 /echo_groups groups/Groups "[data:[1.1, 1.2, 1.3], data:[2.1, 2.2, 2.3]]"

Output:

1.1 1.2 1.3 
2.1 2.2 2.3
edit flag offensive delete link more

Comments

Can you please expand on your answer. Did you do anything special with the Publisher, or left it as is, in the question above?

sharan100 gravatar image sharan100  ( 2017-02-22 23:02:51 -0500 )edit

I have also added a list of errors that I get, besides the main one, on the question.

sharan100 gravatar image sharan100  ( 2017-02-22 23:27:40 -0500 )edit
1

@sharan100 - I update my short answer with example code. It's not the prettiest but it does work.

suforeman gravatar image suforeman  ( 2017-02-23 09:35:55 -0500 )edit

@suforeman This is an excellent way to subscribe, but how would you go about advertising?

sharan100 gravatar image sharan100  ( 2017-02-24 01:58:52 -0500 )edit

Thanks btw!

sharan100 gravatar image sharan100  ( 2017-02-24 01:59:02 -0500 )edit

@suforeman@gvdhoorn Could you please let me know how to approach the Publisher using these messages in the context of my question. I seem to be having quite a bit of problem making that happen.

sharan100 gravatar image sharan100  ( 2017-02-24 06:44:28 -0500 )edit

added CMakeLists.txt to answer

suforeman gravatar image suforeman  ( 2017-02-24 09:03:31 -0500 )edit

Oh, I've figured out what goes on in CMakeLists,txt. I am confused about the publisher right now @suforeman

sharan100 gravatar image sharan100  ( 2017-02-24 09:20:21 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-02-22 08:05:55 -0500

Seen: 10,694 times

Last updated: Mar 07 '17