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

use MultiArray in rosserial

asked 2011-08-23 06:02:38 -0600

atsushi_tsuda gravatar image

updated 2011-08-23 09:31:40 -0600

mjcarroll gravatar image

Hi All

Can we use std_msgs MultiArray in rosserial?
I'm trying following code, but it doesn't work.
The topic has no data.

We are using rosserial of revision 133:db62c6309a50 tip.
Does anyone have suggestion?


#include <ros.h>
#include <std_msgs/Int16.h>
#include <std_msgs/Int16MultiArray.h>

#include <WProgram.h>
#include <Servo.h>

ros::NodeHandle nh;

std_msgs::Int16MultiArray thermo;
ros::Publisher thermo_pub("thermo", &thermo);

char dim0_label[] = "thermo";
void setup()
{
  nh.initNode();
  thermo.layout.dim = (std_msgs::MultiArrayDimension *)
  malloc(sizeof(std_msgs::MultiArrayDimension) * 2);
  thermo.layout.dim[0].label = dim0_label;
  thermo.layout.dim[0].size = 8;
  thermo.layout.dim[0].stride = 1*8;
  thermo.layout.data_offset = 0;
  thermo.data = (int *)malloc(sizeof(int)*8);
  nh.advertise(thermo_pub);
}

void loop()
{
  for(int i = 0; i < 8; i++){
    thermo.data[i] = analogRead(i);
  }
  thermo_pub.publish( &thermo );   
  nh.spinOnce();
  delay(500);
}

the rostopic echo returns

tsuda@tsuda-laptop:~$ rostopic echo /thermo
layout:
 dim: []
 data_offset: 0
data: []
---
edit retag flag offensive close merge delete

Comments

You can also indent a code block by 4 spaces to get it formatted nicely.
dornhege gravatar image dornhege  ( 2011-08-23 06:16:39 -0600 )edit

4 Answers

Sort by ยป oldest newest most voted
5

answered 2011-08-23 06:06:49 -0600

fergs gravatar image

updated 2011-08-23 06:07:02 -0600

Make sure you set the length of your data:

  thermo.layout.dim_length = 1;
  thermo.data_length = 8;

This is necessary since we are using plain old arrays, and not vectors (which would wreak havoc on your AVR by copying, malloc'ing, and other stuffs).

edit flag offensive delete link more

Comments

Thanks. it does work!!
atsushi_tsuda gravatar image atsushi_tsuda  ( 2011-08-23 19:35:01 -0600 )edit
Great, if you could click on the checkmark next to my answer it will mark this question as answered. Thanks!
fergs gravatar image fergs  ( 2011-08-24 04:21:11 -0600 )edit

Is data_length multiplication of all dimension size?

achmad_fathoni gravatar image achmad_fathoni  ( 2019-04-24 06:12:55 -0600 )edit
1

answered 2014-05-20 11:26:57 -0600

jayson ding gravatar image

updated 2014-05-20 11:28:00 -0600

I spent a day to debug this code. It keeps generate "Lost sync with device, restarting..." . Eventually get rid of line thermo.layout.dim_length = 1; fix my problem. Not quite sure what is happen here. I did not have enough time to investigate this. If anyone know the reason, please reply the post. thanks

edit flag offensive delete link more

Comments

Very glad you posted this. I had the same issue. I'm using an arduino uno btw. If I figure out the reason for this, I'll post as well.

pwong gravatar image pwong  ( 2014-06-06 12:32:45 -0600 )edit
2

dim_length value should be your array dimension - 1. So in single dimension array, dim_length should be 0, the default number.

achmad_fathoni gravatar image achmad_fathoni  ( 2019-04-24 06:26:51 -0600 )edit
0

answered 2013-02-21 04:26:44 -0600

Hello,

I have issues using MultiArrays in rosserial (0.3.0), on Groovy and Electric. This is due to the fact that it seems rosserial doesn't handle unsigned variables, and MultiArrayDimension (used in all multi array std_msgs) use unsigned for both size and stride, plus I need to use UInt8MultiArray (array of unsigned 8-bit integers), which makes all the data unusable on the hardware side.

Does anyone has problems using unsigned variables in messages over rosserial ?

Thanks, Cyril

edit flag offensive delete link more

Comments

The unsigned data bug is fixed in trunk.. but we haven't gotten a release out. There should be a new groovy release very shortly.

fergs gravatar image fergs  ( 2013-02-22 13:41:40 -0600 )edit

Thanks for letting me know - are we talking a few days or a few weeks for the Groovy release ? Thanks again Cyril

Cyril Jourdan gravatar image Cyril Jourdan  ( 2013-02-27 05:07:41 -0600 )edit
0

answered 2012-11-18 17:17:43 -0600

PaulBouchier gravatar image

I think the answer given above is correct but incomplete, and was causing me SEGFAULTs on rosserial_embeddedlinux.

Where tsuda did: thermo.layout.dim = (std_msgs::MultiArrayDimension *) malloc(sizeof(std_msgs::MultiArrayDimension) * 2);

dim is a pointer to an object that is getting assigned to the malloc'd memory. (Ignore the fact that twice as much memory is allocated as appears to be needed.) However, the memory malloc'd is allocated but not initialized. Therefore the MultiArrayDimension object's vtable is not initialized, and the subsequent call to thermo_pub.publish( &thermo ); which calls serialize on MultiArrayLayout which calls MultiArrayDimension is using a random vtable pointer when MultiArrayLayout calls this->dim[i].serialize(args...).

tsuda's Arduino would not have segfaulted, but linux does.

The correct implementation is to instantiate a new MultiArrayDimension object with something like: std_msgs::MultiArrayDimension myDim; (this should be done outside of any function, if you need it to persist when the function returns)

tsuda said he got it to work, but maybe not with the code shown here.

Tell me if I'm off in the weeds.

Paul

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2011-08-23 06:02:38 -0600

Seen: 9,735 times

Last updated: May 20 '14