Rosserial thru RS485
Hello,
I am working on a project that has 3 embedded boards for different tasks linked to a PC thru a RS485 bus. We are using RS485 for a lot of reasons, especially because we have limited wires passing thru a small slipring on a joint of the robot.
So, I am trying to run rosserial on an Arduino board thru RS-485 half duplex bus. For this, I'm creating new class, inheriting an ArduinoHardware class and modifying the methods init(), read() and write() to implement the RS485 flow control. In my RS485 tranceptor circuit the pins DE e /RE are tied to a digital output pin of the microcontroller. I named this direction control pin as RTS in the code.
#define RTS 4
class NewHardware : public ArduinoHardware
{
public:
NewHardware():ArduinoHardware(&Serial1, 57600){};
void init(){
pinMode(RTS, OUTPUT);
digitalWrite(RTS, LOW);
iostream->begin(baud_);
}
int read(){
return iostream->read();
};
void write(uint8_t* data, int length){
digitalWrite(RTS, HIGH);
for(int i=0; i<length; i++){
iostream->write(data[i]);
}
while(!(UCSR1A & (1<<TXC1)));
digitalWrite(RTS, LOW);
}
};
ros::NodeHandle_<NewHardware> nh;
It works fine for short messages and low rate publishing. When I increase the size of the messages transmitted or the publishing rate the ros_node.py gives messages of Checksum error or Lost sync with device. For instance, if I run the Adc example, from the ros_lib, that has a big message being published at high rate i get checksum error and a lot of messages about incomplete data. If I put a delay() of 500ms or more at the end of loop() function everything works fine. I also tried the ServiceServer example and nothing works even with a huge delay, but if I comment the publisher part of the the original code the service works fine, but if I try a service response a little bigger the same problems happen.
Here a sample of error messages:
bl@BL-SENAI-PC:~$ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 _baud:=57600
[INFO] [WallTime: 1493993953.096341] ROS Serial Python Node
[INFO] [WallTime: 1493993953.100821] Connecting to /dev/ttyUSB0 at 57600 baud
[INFO] [WallTime: 1493993955.215367] wrong checksum for msg length, length -248
[INFO] [WallTime: 1493993955.216231] chk is 247
[INFO] [WallTime: 1493993955.241712] wrong checksum for topic id and msg
[ERROR] [WallTime: 1493993957.720129] Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [WallTime: 1493993957.721026] Protocol version of client is Rev 0 (rosserial 0.4 and earlier), expected Rev 1 (rosserial 0.5+)
[ERROR] [WallTime: 1493993958.666128] Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [WallTime: 1493993958.667115] Protocol version of client is unrecognized, expected Rev 1 (rosserial 0.5+)
[INFO] [WallTime: 1493993962.715685] wrong checksum for msg length, length -1
[INFO] [WallTime: 1493993962.716585] chk is 255
[ERROR] [WallTime: 1493993968.733170] Mismatched protocol version in packet: lost sync or rosserial_python is from different ros release than the rosserial client
[INFO] [WallTime ...