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

rosserial_arduino can't send a sensor_msgs/Imu msg

asked 2012-01-26 23:11:11 -0500

dlobato gravatar image

Hi,

I have a imu implemented with arduino that I'd like to connect to ros but I got stuck in the most simple thing, sending the Imu message. Sometimes it's it just hang sometimes I get an exception in the python client.

This is the program I'm trying:

#include <ros.h>
#include <sensor_msgs/Imu.h>

ros::NodeHandle  nh;

sensor_msgs::Imu imu_msg;
ros::Publisher imu_pub("imu", &imu_msg);


void setup()
{
  nh.initNode();
  nh.advertise(imu_pub);
  imu_msg.header.frame_id = 0;
  imu_msg.orientation.x = 0.0;
  imu_msg.orientation.y = 0.0;
  imu_msg.orientation.z = 0.0;
  imu_msg.orientation.w = 0.0;
}

void loop()
{
  imu_msg.header.stamp = nh.now();
  imu_pub.publish( &imu_msg );
  nh.spinOnce();
  delay(1000);
}

And this output of the python serial_node:

[INFO] [WallTime: 1327668877.112084] ROS Serial Python Node
[INFO] [WallTime: 1327668877.115963] Connected on /dev/ttyACM0 at 57600 baud
[INFO] [WallTime: 1327668880.075914] Note: publish buffer size is 512 bytes
[INFO] [WallTime: 1327668880.076318] Setup publisher on imu [sensor_msgs/Imu]
Traceback (most recent call last):
  File "/home/dlobato/ros_workspace/rosserial/rosserial_python/nodes/serial_node.py",         line 58, in <module>
    client.run()
  File     "/home/dlobato/ros_workspace/rosserial/rosserial_python/src/rosserial_python/SerialClient.py", line 284, in run
    self.callbacks[topic_id](msg)
  File "/home/dlobato/ros_workspace/rosserial/rosserial_python/src/rosserial_python/SerialClient.py", line 95, in handlePacket
    m.deserialize(data)
  File "/opt/ros/electric/stacks/common_msgs/sensor_msgs/src/sensor_msgs/msg/_Imu.py", line 190, in deserialize
    raise roslib.message.DeserializationError(e) #most likely buffer underfill
roslib.message.DeserializationError: unpack requires a string argument of length 72

If I just change the type of message it works fine, so I think either there's some kind of bug regarding the Imu message or I can't see the problem.

Any idea is welcome! Thanks! David.

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
3

answered 2012-08-06 06:38:30 -0500

dornhege gravatar image

The reason is that the message is just too big for the arduino. There might be some other related questions on this if you look for it.

I did not find a satisfying solution besides sending a float multi array and filling out an Imu message from that manually.

edit flag offensive delete link more
0

answered 2012-01-26 23:40:36 -0500

Lorenz gravatar image

You are setting the frame_id to NULL. I guess that rosserial then cannot serialize it as a string. Try setting frame_id to a valid tf frame or at least to "".

Please note that the quaternion you are publishing is actually not a valid rotation. You should set the w value to 1.0.

edit flag offensive delete link more

Comments

0 means an empty string as well, and yes, I just initialized the quaternion value to 0. Anyway, I've try setting a non-empty string as frame_id and a valid quaternion value and I get the same results. Thanks anyway!
dlobato gravatar image dlobato  ( 2012-01-27 00:19:09 -0500 )edit
In the serialize code for header they use strlen that don't check for NULL strings. My bad. Anyway, as said, using a not null string doesn't change anything.
dlobato gravatar image dlobato  ( 2012-01-27 00:30:53 -0500 )edit
0

answered 2012-08-06 05:48:27 -0500

fs_ros gravatar image

I have run into a similar problem where the rosserial node is unable to process the sensor_msgs/Imu messages. Here is the original arduino code.

#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/Range.h>

ros::NodeHandle  nh;
sensor_msgs::Imu imu_msg;
sensor_msgs::Range range_msg;
ros::Publisher pub_imu( "/imu/data", &imu_msg);
ros::Publisher pub_ran( "/range/test", &range_msg);

void setup()
{ 
  //Serial.begin(9600);
  nh.initNode();
  nh.advertise(pub_imu);
  nh.advertise(pub_ran);
}
void loop()
{
   imu_msg.header.frame_id =  "/imu";
   imu_msg.header.stamp = nh.now();

  pub_imu.publish(&imu_msg);
  pub_ran.publish(&range_msg);
  nh.spinOnce();    

}

Before the node crashes I am able to see an out put via rostopic echo for the test range message, but for the imu/data message just hangs.

fsros@rossvr1:~/sketchbook/libraries/ros_lib$ rosrun rosserial_python serial_node.py /dev/ttyACM0
[INFO] [WallTime: 1344267287.400171] ROS Serial Python Node
[INFO] [WallTime: 1344267287.402094] Connected on /dev/ttyACM0 at 57600 baud
[INFO] [WallTime: 1344267290.351637] Note: publish buffer size is 512 bytes
[INFO] [WallTime: 1344267290.351881] Setup publisher on /imu/data [sensor_msgs/Imu]
[INFO] [WallTime: 1344267290.354571] Setup publisher on /range/test [sensor_msgs/Range]
[INFO] [WallTime: 1344267468.723670] Packet Failed :  Failed to read msg data
Traceback (most recent call last):
  File "/home/fsros/ros_workspace/rosserial/rosserial_python/nodes/serial_node.py", line 58, in <module>
    client.run()
  File "/home/fsros/ros_workspace/rosserial/rosserial_python/src/rosserial_python/SerialClient.py", line 284, in run
    self.callbacks[topic_id](msg)
  File "/home/fsros/ros_workspace/rosserial/rosserial_python/src/rosserial_python/SerialClient.py", line 95, in handlePacket
    m.deserialize(data)
  File "/opt/ros/electric/stacks/common_msgs/sensor_msgs/src/sensor_msgs/msg/_Imu.py", line 190, in deserialize
    raise roslib.message.DeserializationError(e) #most likely buffer underfill
roslib.message.DeserializationError: unpack requires a string argument of length 72
edit flag offensive delete link more

Comments

I have the exact same issue! The publisher just stops publishing without any error and rostopic echo doesnt show any new messages. When I checked the roslogs I found the exact same error. DeserializationError: unpack requires a string argument of length 24! Any idea what fixed this issue?

venktech gravatar image venktech  ( 2019-05-25 19:18:16 -0500 )edit

Question Tools

Stats

Asked: 2012-01-26 23:11:11 -0500

Seen: 4,165 times

Last updated: Aug 06 '12