
I am trying to run base controller on an arduino uno, which will run the motors by subscribing to topics for left and right motor speeds which come through the Twist messages, and also publishes encoder values to topics /lwheel and /rwheel.
When I run the arduino rosserial by connecting it to my PC, there is no problem and everything works fine.
However, when I connect the uno to my raspberry pi, which is connected to my PC, problems occur. I notice the following messages and errors on my terminal running the command rosrun rosserial_python serial_node.py /dev/ttyACM0 :
[INFO] [1577335551.127150]: Connecting to /dev/ttyACM0 at 57600 baud
[INFO] [1577335553.249219]: Requesting topics...
[INFO] [1577335553.290434]: Note: publish buffer size is 512 bytes
[INFO] [1577335553.298687]: Setup publisher on lwheel [std_msgs/Float32]
[INFO] [1577335553.321495]: Setup publisher on rwheel [std_msgs/Float32]
[INFO] [1577335553.348951]: Note: subscribe buffer size is 512 bytes
[INFO] [1577335553.357481]: Setup subscriber on left_wheel_speed [std_msgs/Float32]
[INFO] [1577335553.386113]: Setup subscriber on right_wheel_speed [std_msgs/Float32]
[INFO] [1577335556.177063]: wrong checksum for topic id and msg
[INFO] [1577335559.040959]: wrong checksum for topic id and msg
[ERROR] [1577335561.888282]: Mismatched protocol version in packet ('\x00'): lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [1577335561.896526]: Protocol version of client is unrecognized, expected Rev 1 (rosserial 0.5+)
[INFO] [1577335564.716741]: wrong checksum for topic id and msg
[ERROR] [1577335579.781605]: Lost sync with device, restarting...
[INFO] [1577335579.790889]: Requesting topics...
[INFO] [1577335579.826395]: Setup publisher on lwheel [std_msgs/Float32]
[INFO] [1577335579.839117]: Setup publisher on rwheel [std_msgs/Float32]
[INFO] [1577335582.842464]: wrong checksum for msg length, length 4
[INFO] [1577335582.850964]: chk is 0
These messages are repeated over and over. I also notice weird behavior in the robot itself. There is random latency between my key press and actual movement, and the longer I press the key, the longer it continues that movement "after" I release the key.
I thought it might be an issue with the uno's dynamic memory size. So I shifted to arduino mega. It uses 28% of its dynamic memory, but I face the same issue with Arduino Mega. I don't think its an issue with buffer as well, because it works well when connected directly to the PC. I am running Ubuntu 16.04 and ROS Kinetic on PC, and Ubuntu Mate 18.04 and ROS Melodic on Raspberry Pi Model 3 B. Can that be the cause? If yes, then why isn't that causing problems when I have no publishers? (The uno works perfectly well when the code is just subscribing to speed topics and running motors, even when connected to pi).
Arduino Code:
#include <ros.h>
#include <std_msgs/Float32.h>
#include "Arduino.h"
ros::NodeHandle nh;
// Left encoder
int Left_Encoder_PinA = 2;
int Left_Encoder_PinB = 9;
volatile long Left_Encoder_Ticks = 0;
//Variable to read current state of left encoder pin
volatile bool LeftEncoderBSet;
//Right Encoder
int Right_Encoder_PinA = 3;
int Right_Encoder_PinB = 10;
volatile long Right_Encoder_Ticks = 0;
//Variable to read current state of right encoder pin
volatile bool RightEncoderBSet;
// Left Motor
int enA = 6;//3
int dir1 = 5;
// Right Motor
int enB = 11;//9
int dir2 = 8;
//Initialising with defaults to keep the motors stopped
bool leftdir = 1, rightdir = 1;
int leftanalog = 255, rightanalog = 255;
//float lwheelv = 0;//left wheel velocity command
//float rwheelv = 0;//right wheel velocity from twist_to_motors
//Returns an Analog value for the given speed from twist to motors script
int speedConv(float x, float in_min, float in_max, float out_min, float out_max) {
int analogval = (int( (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min));
if (analogval < 0)
analogval = 0;
else if (analogval > 255)
analogval = 255;
return (analogval);
}
//Sets Direction and Speed value for left motor
void setleft(float val)
{
if (val < 0.0)
{
leftdir = 0;
val = val * (-1);
leftanalog = speedConv(val, 0.0, 0.2, 0.0, 255.0);
}
else
{
leftdir = 1;
leftanalog = speedConv(val, 0.0, 0.2, 255.0, 0.0);
}
}
//Sers Direction and Speed value for left motor
void setright(float val)
{
if (val < 0.0)
{
rightdir = 0;
val = val * (-1);
rightanalog = speedConv(val, 0.0, 0.2, 0.0, 255.0);
}
else
{
rightdir = 1;
rightanalog = speedConv(val, 0.0, 0.2, 255.0, 0.0);
}
}
//Runs the left motor with above direction and speed values
void leftmotor(const std_msgs::Float32 data) // 1 for clcckwise 2 for anti clockwise
{
float lwheelv = 0.0;
lwheelv = data.data;
setleft(lwheelv);
if (leftdir)
{
digitalWrite(dir1, HIGH);
}
else if (!leftdir)
{
digitalWrite(dir1, LOW);
}
else {
Serial.println(F("Wrong direction set for MA!!"));
}
analogWrite(enA, leftanalog);
}
//Runs the right motor with above direction and speed values
void rightmotor(const std_msgs::Float32 data) // 1 for clockwise 2 for anti clockwise
{
float rwheelv = 0.0;
rwheelv = data.data;
setright(rwheelv);
if (rightdir)
{
digitalWrite(dir2, HIGH);
}
else if (!rightdir)
{
digitalWrite(dir2, LOW);
}
else {
Serial.println(F("Wrong direction set for MB!!"));
}
analogWrite(enB, rightanalog);
}
std_msgs::Float32 a;
std_msgs::Float32 b;
//Publish steps of left and right stepper motors
ros::Publisher pub1("lwheel", &a);
ros::Publisher pub2("rwheel", &b);
//Publish steps of left and right stepper motors
//Subscribe to left and right wheel velocity topics
ros::Subscriber<std_msgs::Float32> subl("left_wheel_speed", &leftmotor);
ros::Subscriber<std_msgs::Float32> subr("right_wheel_speed", &rightmotor);
void setup()
{
//Initialise node and subscribe to necessary topics
nh.initNode();
nh.subscribe(subl);
nh.subscribe(subr);
nh.advertise(pub1);
nh.advertise(pub2);
Serial.begin(57600);
SetupEncoders();
//Define motor pins as output pins
pinMode(enA, OUTPUT);
pinMode(enB, OUTPUT);
pinMode(dir1, OUTPUT);
pinMode(dir2, OUTPUT);
}
void SetupEncoders()
{
// Quadrature encoders
// Left encoder
pinMode(Left_Encoder_PinA, INPUT); // sets pin A pullup
pinMode(Left_Encoder_PinB, INPUT); // sets pin B pullup
attachInterrupt(digitalPinToInterrupt(Left_Encoder_PinA), do_Left_Encoder, RISING);
// Right encoder
pinMode(Right_Encoder_PinA, INPUT); // sets pin A pullup
pinMode(Right_Encoder_PinB, INPUT); // sets pin B pullup
attachInterrupt(digitalPinToInterrupt(Right_Encoder_PinA), do_Right_Encoder, RISING);
}
void loop()
{
a.data = Left_Encoder_Ticks;
b.data = Right_Encoder_Ticks;
pub1.publish(&a);
pub2.publish(&b);
nh.spinOnce();
delayMicroseconds(10);
}
void do_Left_Encoder()
{
LeftEncoderBSet = digitalRead(Left_Encoder_PinB); // read the input pin
Left_Encoder_Ticks += LeftEncoderBSet ? -1 : +1;
}
void do_Right_Encoder()
{
RightEncoderBSet = digitalRead(Right_Encoder_PinB); // read the input pin
Right_Encoder_Ticks += RightEncoderBSet ? +1 : -1;
}
Originally posted by parzival on ROS Answers with karma: 463 on 2019-12-26
Post score: 1
Original comments
Comment by gvdhoorn on 2019-12-26:
I'm not an arduino expert, but you appear to be using Serial and rosserial at the same time, with the same serial port.
That is not supported.
Remove the Serial.begin() and Serial.println(..) calls and try again.
Comment by parzival on 2019-12-27:
Hi @gvdhoorn that wasn't a problem when just running motors. However, I'll try that
Comment by parzival on 2019-12-27:
@gvdhoorn I tried your suggestion, but still the same problem.
Comment by gvdhoorn on 2019-12-27:
Regardless of whether it solves your problem, you cannot use Serial together with rosserial. Unless you've changed the serial hw rosserial should use (on the Arduino side, not the ROS side).