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

Rosserial arduino - wrong checksum and mismatched protocol errors

asked 2020-08-13 16:51:17 -0500

hvak gravatar image

updated 2022-08-07 08:59:19 -0500

lucasw gravatar image

Hi everyone.

My arduino uno is publishing std_msgs/Int16 messages over two topics, one for each wheels encoder ticks. It connects to rosserial on a raspberry pi 4 and data is published just fine, but I see errors/warnings that sometimes interrupt the data. These include:

[INFO] [1597354299.800672]: wrong checksum for topic id and msg

[ERROR] [1597354307.941502]: Mismatched protocol version in packet ('\x00'): lost sync or rosserial_python is from different ros release than the rosserial client

Occasionally, it also looses sync with the arduino:

[ERROR] [1597353144.897853]: Lost sync with device, restarting...

Here is my arduino code:

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

//ROS
ros::NodeHandle node;
std_msgs::Int16 lWheelMsg;
std_msgs::Int16 rWheelMsg;
ros::Publisher lWheelPub("/lwheel", &lWheelMsg);
ros::Publisher rWheelPub("/rwheel", &rWheelMsg);

//Encoder
const int LEFT_ENCODER_PIN = 9;
const int RIGHT_ENCODER_PIN = 10;
RedBotEncoder encoder = RedBotEncoder(LEFT_ENCODER_PIN, RIGHT_ENCODER_PIN);//left, right
int countsPerRev = 192;   // 4 pairs of N-S x 48:1 gearbox = 192 ticks per wheel rev
int16_t lWheelTicks = 0;
int16_t rWheelTicks = 0;

void setup()
{
  //initialize ros
  node.initNode();
  node.advertise(lWheelPub);
  node.advertise(rWheelPub);

  //reset encoders
  encoder.clearEnc(BOTH);

}

void loop() 
{

  //send encoder data over ROS
  lWheelTicks = encoder.getTicks(LEFT);
  rWheelTicks = encoder.getTicks(RIGHT);
  lWheelMsg.data = lWheelTicks;
  rWheelMsg.data = rWheelTicks;
  lWheelPub.publish(&lWheelMsg);
  rWheelPub.publish(&rWheelMsg);

  node.spinOnce();
  delay(200);
}

Any idea what could be causing this? Thanks!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-08-16 08:43:20 -0500

Andy West gravatar image

The delay is most likely causing the system to foul up. ROSSerial tries to communicate with the arduino every so often, if it's during this delay then everything falls over.

Instead of delay(200); use millis();to check current arduino clock time. If it has been at least 200 ms since the last message, then publish the data. Check out this article on how to use this (https://learn.adafruit.com/multi-task...).

As a rough guide:

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

//ROS
ros::NodeHandle node;
std_msgs::Int16 msg;
ros::Publisher msgPub("my_topicl", &msg);

unsigned long pubPeriod = 200; // milliseconds between publishing data
unsigned long previousTime;
int seq = 0;

void setup()
{
  //initialize ros
  node.initNode();
  node.advertise(msgPub);

  previousTime = 0;
}

void loop()
{

  if (previousTime + pubPeriod <= millis()){
    // Do actions after pubPeriod since last published message

    msg.data = seq;
    msgPub.publish(&msg);

    previousTime = millis();
    seq++;
  }
  nh.spinOnce();
  delay(1);

}

Hope this helps.

edit flag offensive delete link more

Comments

This solved my issue, thank you!

hvak gravatar image hvak  ( 2020-08-21 13:02:50 -0500 )edit

Yay! Glad to be of help.

Andy West gravatar image Andy West  ( 2020-08-22 09:22:56 -0500 )edit

Question Tools

Stats

Asked: 2020-08-13 16:51:17 -0500

Seen: 490 times

Last updated: Aug 16 '20