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

rosserial fails when using sensor_msgs::Imu

asked 2013-10-15 13:57:28 -0500

Dereck gravatar image

updated 2013-11-18 19:21:08 -0500

tfoote gravatar image

I am attempting to send IMU messages to ROS from an Arduino and was making good progress until last night... I can send all sorts of primitive messages, and messages which contain other primitives, but for some reason the IMU message doesn't make it to rostopic echo /imu. Code attached, please advise:

$ rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0
[INFO] [WallTime: 1381881252.718444] ROS Serial Python Node
[INFO] [WallTime: 1381881252.726693] Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [WallTime: 1381881255.329399] Note: publish buffer size is 512 bytes
[INFO] [WallTime: 1381881255.329896] Setup publisher on imu [sensor_msgs/Imu]
[ERROR] [WallTime: 1381881272.931531] Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [WallTime: 1381881272.931971] Protocol version of client is Rev 0 (rosserial 0.4 and earlier), expected Rev 1 (rosserial 0.5+)

...

genpy.message.DeserializationError: unpack requires a string argument of length 32

Which is thrown from this line of _Imu.py:

(_x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w,) = _struct_4d.unpack(str[start:end])

Here's my sketch code:

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

ros::NodeHandle  nh;
sensor_msgs::Imu imu_msg;
ros::Publisher pub("imu", &imu_msg);
char frame_id[] = "imu";

void setup(){  
  nh.initNode();
  nh.advertise(pub);

  imu_msg.header.seq = 0;
  imu_msg.header.stamp = nh.now();
  imu_msg.header.frame_id = frame_id;


  imu_msg.orientation.x = 0;
  imu_msg.orientation.y = 0;
  imu_msg.orientation.z = 0;
  imu_msg.orientation.w = 0;

  imu_msg.orientation_covariance[0] = 0;
  imu_msg.orientation_covariance[1] = 0;
  imu_msg.orientation_covariance[2] = 0;

  imu_msg.orientation_covariance[3] = 0;
  imu_msg.orientation_covariance[4] = 0;
  imu_msg.orientation_covariance[5] = 0;

  imu_msg.orientation_covariance[6] = 0;
  imu_msg.orientation_covariance[7] = 0;
  imu_msg.orientation_covariance[8] = 0;


  imu_msg.angular_velocity.x = 0;
  imu_msg.angular_velocity.y = 0;
  imu_msg.angular_velocity.z = 0;

  imu_msg.angular_velocity_covariance[0] = 0;
  imu_msg.angular_velocity_covariance[1] = 0;
  imu_msg.angular_velocity_covariance[2] = 0;

  imu_msg.angular_velocity_covariance[3] = 0;
  imu_msg.angular_velocity_covariance[4] = 0;
  imu_msg.angular_velocity_covariance[5] = 0;

  imu_msg.angular_velocity_covariance[6] = 0;
  imu_msg.angular_velocity_covariance[7] = 0;
  imu_msg.angular_velocity_covariance[8] = 0;


  imu_msg.linear_acceleration.x = 0;
  imu_msg.linear_acceleration.y = 0;
  imu_msg.linear_acceleration.z = 0;

  imu_msg.linear_acceleration_covariance[0] = 0;
  imu_msg.linear_acceleration_covariance[1] = 0;
  imu_msg.linear_acceleration_covariance[2] = 0;

  imu_msg.linear_acceleration_covariance[3] = 0;
  imu_msg.linear_acceleration_covariance[4] = 0;
  imu_msg.linear_acceleration_covariance[5] = 0;

  imu_msg.linear_acceleration_covariance[6] = 0;
  imu_msg.linear_acceleration_covariance[7] = 0;
  imu_msg.linear_acceleration_covariance[8] = 0;
}

void loop(){

  imu_msg.header.seq++;
  imu_msg.header.stamp = nh.now();

  // Doesn't work:
  pub.publish(&imu_msg);

  // These work:
  // pub.publish(&imu_msg.header);
  // pub.publish(&imu_msg.orientation);
  // pub.publish(&imu_msg.angular_velocity);

  // This doesn't
  nh.spinOnce();
  delay(500);
}
edit retag flag offensive close merge delete

Comments

thanks for sharing your sketch code, it helped me a lot. But why is it working with setting every value to zero? Because of that the imu_message is literally empty.

colidar gravatar image colidar  ( 2019-07-23 08:27:08 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2013-10-24 14:15:52 -0500

Dereck gravatar image

The IMU message is too large for the Arduino serial port buffer: http://answers.ros.org/question/12782/rosserial_arduino-cant-send-a-sensor_msgsimu-msg/

The solution is to send a float array via serial and then convert that to an IMU message in another node.

edit flag offensive delete link more

Comments

got the same error while trying to receive from arduino

marwa eldiwiny gravatar image marwa eldiwiny  ( 2016-11-13 00:04:26 -0500 )edit

Depending on your board (UNO/M0/...) you can search for the define #define SERIAL_BUFFER_SIZE 64" in the arduino framework and increase it :-) Look for a file named RingBuffer.h

Markus Bader gravatar image Markus Bader  ( 2016-11-13 03:31:29 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2013-10-15 13:57:28 -0500

Seen: 2,473 times

Last updated: Nov 13 '16