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

ROS Arduino message type restrictions?

asked 2014-12-14 23:06:31 -0500

Gariben gravatar image

updated 2014-12-15 08:39:25 -0500

I'm getting a 'mismatched protocol' error when publishing a message (UInt8) from an Arduino to ROS:

Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client

It should be noted that the message still works, I'm just a bit concerned about the error message and would like to learn more about it.

There's a lot of threads around ROS answers stating that people are getting the error from rosserial because their message of choice was too large (message types such as IMU, etc.)

I took a look at the rosserial limitations and saw that for my particular board (ATMEGA328) that the buffer size is 280 bytes. Shouldn't the Uint8 type in theory only be 8 bytes, or is there something I'm missing?

Here are all of the ROS components from my program:

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


ros::NodeHandle nh;
std_msgs::UInt8 ROS_int;
ros::Publisher state("Device_state", &ROS_int);

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

}

void loop(){

 ROS_int.data = CurrentState;
 state.publish( &ROS_int );
 nh.spinOnce();

Is it perhaps that I'm using some outdated syntax on something?

Edit #1: @ahendrix I can see the messages on the ROS side, I haven't checked the frequency... but the error could be related to that. Here's an example screenshot from when I'm echoing the value vs. what rosserial is telling me. It does seem inconsistent. Does it have something to do with my setting perhaps? I may just try flashing it as Wolf suggests.

image description

@Wolf I'm running Hydro on the laptop, and the ros_lib on the arduino is a few months old? perhaps. I remember in September or something I initially downloaded that, I'll give it a try and see if that fixes.

edit retag flag offensive close merge delete

Comments

The UInt8 should be 8 bits or 1 byte. Can you see published messages on the ROS side? If they're at a constant frequency, do you miss a message every time you see an error?

ahendrix gravatar image ahendrix  ( 2014-12-15 02:38:02 -0500 )edit
1

Probably stupid question: did you recently update the code on your device? I just a couple of sconds ago happend to have the same issue due to a ROS update; regenerating arduino ros_lib and flashing the device with code compiled against new ros_lib fixed it for me :)

Wolf gravatar image Wolf  ( 2014-12-15 03:01:23 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2014-12-16 01:30:15 -0500

ahendrix gravatar image

This looks less like a protocol mismatch, and more like you have garbled data on your serial line. In particular, I see lots of messages complaining that checksums on various parts of the message are wrong, and they seem to spread across lots of different parts of the message, not just the type field.

There are a couple of ways that this could be happening: 1. Incomplete messages are getting transmitted. Normally the arduino libraries should prevent this, but it can happen if you're trying to transmit data from inside an interrupt handler. 1. You're sending raw data out the serial port, and its confusing rosserial. 1. Your USB to serial chip is dropping bytes. 1. There's electrical noise in your system.

To approach the first problem, you should look through your code and make sure that there's only one place where you call publish. Preferably not in an interrupt handler.

Don't do #2. If there's anywhere in your program that you're using Serial.print or similar functions, remove them.

If you're still having problems, it's possible that your USB to serial chip is dropping bytes. In particular, my experience with the newer arduinos that don't use the FTDI chip have trouble with higher baud rates like 115.2k. Try lowering your baud rate to see if that helps.

If you're still having trouble, it's possible that there's some kind of electrical noise on your serial line. If you're using an arduino with a built-in USB port, this is incredibly unlikely. If you have your serial lines running over exposed wires, it's more likely. If you're tried everything else and are still having problems, you can try hooking an oscilloscope to the serial lines and looking at the signal quality.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-12-14 22:59:24 -0500

Seen: 4,726 times

Last updated: Dec 16 '14