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

Float32MultiArray in pub/sub example

asked 2023-08-07 09:24:12 -0600

Lilipop gravatar image

updated 2023-08-07 09:28:04 -0600

Hello ROS people,

so basically, I am simply trying to reproduce a simple C++ pub/sub example using the Float32MultiArray type. Here are the codes :

SUBSCRIBER

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "std_msgs/Float32MultiArray.h"
void subscriberCallback(const std_msgs::Float32MultiArray::ConstPtr& test)
{
for(int i=0; i<5;i++){
    ROS_INFO("I heard %d: %f\n", i, test->data[i]);
}}
int main(int argc, char **argv){
 ros::init(argc, argv, "subscriber");
 ros::NodeHandle n;
 ros::Subscriber sub = n.subscribe("subscriber_topic", 1000, subscriberCallback);
 ros::spin();
 return 0;
 }

PUBLISHER

#include <stdio.h>
#include "ros/ros.h"
#include "std_msgs/Float32MultiArray.h"
int main(int argc, char **argv){
ros::init(argc, argv, "publisher");
ros::NodeHandle n;
ros::Publisher pub = n.advertise<std_msgs::Float32MultiArray>("subscriber_topic", 10);
ros::Rate rate(10);
while (ros::ok()){
std_msgs::Float32MultiArray data;
for(int i=0;i<5;i++){data.data[i]=i;}
pub.publish(data);
ros::spinOnce();
rate.sleep();
}
return 0;
}

1- The catkin_make build gives no error at all.

2- If I launch the subscriber node and publish on the terminal to subscriber_topic F32MA data, everything goes fine, which means the problem is from the publisher side.

3- When launching the publisher node, here is the error (exit code -11 ? searched and didn't find anything around that) - couldn't put a screen -

SUMMARY
========

PARAMETERS
* /rosdistro: melodic
* /rosversion: 1.14.13

NODES
/
publisher (publisher/publisher)

ROS_MASTER_URI=http://localhost:11311

process[publisher-1]: started with pid [1332]
[publisher-1] process has died [pid 1332, exit code -11, cmd 
/home/lilialkalee/f32ma/devel/lib/publisher/publisher __name:=publisher 
__log:=/home/lilialkalee/.ros/log/ab233984-352b-11ee-accc-00155dae808d/publisher-1.log].
log file: /home/lilialkalee/.ros/log/ab233984-352b-11ee-accc-00155dae808d/publisher-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Btw, when I look for the log given with the path /home/lilialkalee/.ros/log/ab233984-352b-11ee-accc-00155dae808d/publisher-1.log, the publisher-1.log cannot be found xD

So, any clues ? and thanks in advance.

edit retag flag offensive close merge delete

Comments

1

Here's an example that does work. I'm guessing your problem is that in this chunk data.data[i]=i; you have not told the computer that the data.data vector should have 5 entries. So you are trying to access uninitialized memory. You should likely be using something like push_back or data.data.resize(5); before your for loop in the publisher.

jarvisschultz gravatar image jarvisschultz  ( 2023-08-07 15:03:48 -0600 )edit
1

If you look at the example above, you'll see that I use push_back on Float32MultiArray.layout to set the size of that vector, and then I use std::vector::resize to resize a vector that will contain the data I'm trying to publish (which I eventually set equal to Float32MultiArray.data).

Side note, I believe the exit code -11 is coming from Python's subprocess poll function which, according to that link, would indicate your program exiting due to a signal 11. Note, roslaunch is written in Python and uses the subprocess module to run nodes. This would correspond to a SIGSEGV -- which is an invalid memory reference. This is consistent with my previous comment.

jarvisschultz gravatar image jarvisschultz  ( 2023-08-07 17:37:06 -0600 )edit

Hey, thanks a lot for the detailed answer. With the resize function now, I am able to get a functionning publisher !

Thanks again for your explanation :)

Lilipop gravatar image Lilipop  ( 2023-08-08 03:53:28 -0600 )edit

Cool. I'm going to convert these to an answer so that this shows up as answered. If you wouldn't mind accepting that would be helpful too.

jarvisschultz gravatar image jarvisschultz  ( 2023-08-09 11:44:13 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2023-08-09 11:44:45 -0600

Here's an example that does work. I'm guessing your problem is that in this chunk data.data[i]=i; you have not told the computer that the data.data vector should have 5 entries. So you are trying to access uninitialized memory. You should likely be using something like push_back or data.data.resize(5); before your for loop in the publisher.

If you look at the example above, you'll see that I use push_back on Float32MultiArray.layout to set the size of that vector, and then I use std::vector::resize to resize a vector that will contain the data I'm trying to publish (which I eventually set equal to Float32MultiArray.data).

Side note, I believe the exit code -11 is coming from Python's subprocess poll function which, according to that link, would indicate your program exiting due to a signal 11. Note, roslaunch is written in Python and uses the subprocess module to run nodes. This would correspond to a SIGSEGV -- which is an invalid memory reference. This is consistent with my previous comment.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2023-08-07 09:24:12 -0600

Seen: 992 times

Last updated: Aug 09 '23