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

How to initialize a UInt8MultiArray message

asked 2012-06-25 02:05:37 -0500

ipso gravatar image

updated 2012-06-25 05:13:01 -0500

Not too much info on these (or any of the variants) on the wiki: what is the proper way to initialize these? I've tried:

const unsigned int data_sz = 10;
std_msgs::UInt8MultiArray m;

m.layout.dim.push_back(std_msgs::MultiArrayDimension());
m.layout.dim[0].size = data_sz;
m.layout.dim[0].stride = 1;
m.layout.dim[0].label = "bla";

// only needed if you don't want to use push_back
m.data.resize(data_sz);

for an array with 10, 1 byte elements, but I keep getting segfaults at the subscriber callback when accessing the data member (FIXED: see edit).

I couldn't find any examples anywhere, apart from http://alexsleat.co.uk/tag/multiarray/, but those snippets do not initialize any dimensions.

Is it programmers responsibility to keep the dimension objects in sync with the actual size of the data member, or is ROS doing some magic behind the scenes at serialization?


edit: as @Lorenz commented: reserve -> resize. I've left the bit about the segfaults in the question, even though that was fixed.

edit retag flag offensive close merge delete

Comments

1

reserve might not do what you expect. It just causes the vector to allocate more memory but doesn't change its size, i.e. a call to vector's size method will still return 0. Instead, use the method resize.

Lorenz gravatar image Lorenz  ( 2012-06-25 02:19:34 -0500 )edit
1

yes, just GDBed myself to that conclusion as well. Should've read the docs more carefully. Thanks for your reply. Point about the documentation on the whole MultiArray thing being really thin / non existent stands though (imho).

ipso gravatar image ipso  ( 2012-06-25 02:26:03 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
0

answered 2012-06-26 09:28:03 -0500

ipso gravatar image

The snippet in my original post is basically how you initialize MultiArrays. Just push_back() a new std_msgs::MultiArrayDimension for each dimension and set it up according to the docs @Lorenz referenced.

Using resize(n, std_msgs::MultiArrayDimension()) should also work.

edit flag offensive delete link more

Comments

could you please extend on it via the push_back() approach?

user23fj239 gravatar image user23fj239  ( 2016-02-15 14:02:34 -0500 )edit
3

answered 2017-04-26 05:32:51 -0500

mtROS gravatar image

updated 2017-04-26 05:36:50 -0500

Hy, following a working code tried on an Arduino Mega and ROS Kinetic: Commands in ROS:

$ roscore

//New terminal

$ rosrun rosserial_python serial_node.py /dev/ttyACM0 _baud:=115200

//New terminal

$ rostopic echo /arr

Arduino Code for Publishing an array with 4 words:

#include <ros.h>
#include <std_msgs/UInt16MultiArray.h>

ros::NodeHandle nh;

std_msgs::UInt16MultiArray arr;
ros::Publisher pub_arr( "/arr", &arr);

void setup() {
  nh.getHardware()->setBaud(115200);
  nh.initNode();
  arr.layout.dim = (std_msgs::MultiArrayDimension *)
  malloc(sizeof(std_msgs::MultiArrayDimension)*2);
  arr.layout.dim[0].label = "height";
  arr.layout.dim[0].size = 4;
  arr.layout.dim[0].stride = 1;
  arr.layout.data_offset = 0;
  arr.data = (int *)malloc(sizeof(int)*8);
  arr.data_length = 4;
  nh.advertise(pub_arr);

}

void loop() {    
  arr.data[0] = 1;
  arr.data[1] = 2;
  arr.data[2] = 3;
  arr.data[3] = 4; 
  pub_arr.publish(&arr);
  nh.spinOnce();
}
edit flag offensive delete link more
2

answered 2012-06-25 02:35:07 -0500

Lorenz gravatar image

Have a look at the definition of the messages. The file UInt8MultiArray contains a comment:

# Please look at the MultiArrayLayout message definition for
# documentation on all multiarrays.

The file MultiArrayLayout.msg contains the following:

# The multiarray declares a generic multi-dimensional array of a
# particular data type.  Dimensions are ordered from outer most
# to inner most.

MultiArrayDimension[] dim # Array of dimension properties
uint32 data_offset        # padding bytes at front of data

# Accessors should ALWAYS be written in terms of dimension stride
# and specified outer-most dimension first.
# 
# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
#
# A standard, 3-channel 640x480 image with interleaved color channels
# would be specified as:
#
# dim[0].label  = "height"
# dim[0].size   = 480
# dim[0].stride = 3*640*480 = 921600  (note dim[0] stride is just size of image)
# dim[1].label  = "width"
# dim[1].size   = 640
# dim[1].stride = 3*640 = 1920
# dim[2].label  = "channel"
# dim[2].size   = 3
# dim[2].stride = 3
#
# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
edit flag offensive delete link more

Comments

2

Thanks. I've actually read those comments in the msg def. I guess my question was more 'why are there so few (none) actual (C++) examples for this?' than 'what is the meaning of all these fields?'. Simultaneously programming in 3+ languages also doesn't help.

ipso gravatar image ipso  ( 2012-06-25 04:39:01 -0500 )edit
1

I guess people just don't use this kind of really generic messages. It's always better to define a message with meaningful slot names instead of using generic message types for everything.

Lorenz gravatar image Lorenz  ( 2012-06-25 04:43:00 -0500 )edit

Could someone extend on how to create multiple arrays I dont get the dim[i]-stuff and where to put it ? Also why push an multiarray into the same multiarray, m.layout.dim.push_back(std_msgs::MultiArrayDimension());

user23fj239 gravatar image user23fj239  ( 2016-02-15 08:25:00 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-06-25 02:05:37 -0500

Seen: 22,685 times

Last updated: Apr 26 '17