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

rosserial deserialization error

asked 2013-08-19 12:22:22 -0500

dan gravatar image

updated 2013-08-19 17:58:30 -0500

I am trying to publish an odometry message from an arduino using rosserial. I have it publishing a tf message fine. But the odom message first required increasing the buffer_size and now gives this error:

[INFO] [WallTime: 1376950638.665497] ROS Serial Python Node
[INFO] [WallTime: 1376950638.671086] Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [WallTime: 1376950641.232339] Note: publish buffer size is 1024 bytes
[INFO] [WallTime: 1376950641.232938] Setup publisher on tf [tf/tfMessage]
[INFO] [WallTime: 1376950641.242256] Setup publisher on odom [nav_msgs/Odometry]
Traceback (most recent call last):
  File ".../catkin_ws/src/rosserial/rosserial_python/nodes/serial_node.py", line 82, in <module>
    client.run()
  File ".../catkin_ws/install/lib/python2.7/dist-packages/rosserial_python/SerialClient.py", line 425, in run
    self.callbacks[topic_id](msg)
  File ".../catkin_ws/install/lib/python2.7/dist-packages/rosserial_python/SerialClient.py", line 99, in handlePacket
    m.deserialize(data)
  File "/opt/ros/groovy/lib/python2.7/dist-packages/nav_msgs/msg/_Odometry.py", line 220, in deserialize
    raise genpy.DeserializationError(e) #most likely buffer underfill
genpy.message.DeserializationError: unpack requires a string argument of length 288

Sometimes, about one in three, there is also this error right after the INFO messages shown above. I suspect it is just some sort of lost sync, since I just installed the latest version of rosserial on a new build of Groovy.

[ERROR] [WallTime: 1376951210.467803] Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [WallTime: 1376951210.468270] Protocol version of client is Rev 0 (rosserial 0.4 and earlier), expected Rev 1 (rosserial 0.5+)

Here is the code:

/* 
 * rosserial Planar Odometry Example
 */

#include <ros.h>
#include <ros/time.h>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>

ros::NodeHandle  nh;

geometry_msgs::TransformStamped t;
tf::TransformBroadcaster broadcaster;
nav_msgs::Odometry myOdom;
ros::Publisher odom_pub("odom", &myOdom);

double x = 1.0;
double y = 0.0;
double theta = 1.57;

char base_link[] = "/base_link";
char odom[] = "/odom";

void setup()
{
  nh.initNode();
  broadcaster.init(nh);
  nh.advertise(odom_pub);
  myOdom.pose.covariance = {0.001, 0, 0, 0, 0, 0, // covariance on x
                        0, 0.001, 0, 0, 0, 0,  // covariance on y
                        0, 0, 0.001, 0, 0, 0,  // covariance on z
                        0, 0, 0, 99999, 0, 0,  // large covariance on rot x
                        0, 0, 0, 0, 99999, 0,  // large covariance on rot y
                        0, 0, 0, 0, 0, 0.001};  //covariance on rot z

}

void loop()
{  
  // drive in a circle
  double vx = 0.2, vy = 0.2;
  double vtheta = 0.18;
  x += cos(theta)*vx*0.1;
  y += sin(theta)*vy*0.1;
  theta += vtheta*0.1;
  if(theta > 3.14)
    theta=-3.14;

  /* 
  Serial.print("x , y, theta = ");
  Serial.print(x);
  Serial.print(", ");
  Serial.print(y);
  Serial.print(", ");
  Serial.println(theta);
  */

  // tf odom->base_link
  t.header.frame_id = odom;
  t.child_frame_id = base_link;

  t.transform.translation.x = x;
  t.transform.translation.y = y;

  t.transform.rotation = tf::createQuaternionFromYaw(theta);
  t.header.stamp = nh.now();

  broadcaster.sendTransform(t);
  nh.spinOnce();

  myOdom.header.stamp = nh.now();
  myOdom.header.frame_id ...
(more)
edit retag flag offensive close merge delete

Comments

problem resolved in this pull request https://github.com/ros-drivers/rosserial/pull/106

linvinus gravatar image linvinus  ( 2014-03-11 22:55:49 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
0

answered 2013-08-19 19:41:34 -0500

ahendrix gravatar image

The Odometry message is huge (700+ bytes if I remember properly). This is WAY too big to publish from an arduino.

I suggest you either look at the alternative http://ros.org/wiki/ros_arduino_bridge or look into publishing a simpler message and writing a separate node to convert it into a full Odometry message.

edit flag offensive delete link more

Comments

Why is < 1000 bytes too big? I increased the buffer_size to 1024 and am using a mega 2560.

dan gravatar image dan  ( 2013-08-20 07:44:18 -0500 )edit

I have the same problem.Do you solve it now?

demi gravatar image demi  ( 2017-08-21 04:20:37 -0500 )edit
0

answered 2016-11-23 15:36:16 -0500

Void gravatar image

In addition to the correct versions, you need to have #include <ros.h> at the top of the code, ros::NodeHandle nh; declared as a global, nh.initNode(); and Serial.begin(115200); within void setup(), and nh.spinOnce(); within void loop().

edit flag offensive delete link more
0

answered 2018-06-28 11:27:52 -0500

Mark Rose gravatar image

updated 2018-06-28 11:29:53 -0500

You need an output buffer large enough to hold all messages published between calls to spinOnce(). (When you call spinOnce(), all queued, published messages are sent, and incoming messages are retrieved into the input buffer.)

On a Mega you're probably OK memory-wise. I'm working with a 2kb Arduino-compatible, and have abandoned rosserial because of the large memory footprint. I second the suggestion of ros_arduino_bridge as an alternative.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2013-08-19 12:22:22 -0500

Seen: 4,532 times

Last updated: Jun 28 '18