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

[SOLVED] Serial Port read returned short error with arduino uno via bluetootle with rosserial

asked 2014-09-10 02:28:17 -0500

EwingKang gravatar image

updated 2015-03-22 21:08:27 -0500

Hi all!

I'm working with arduino car under directly ROS topic command. I have a arduino uno board with Arduino Sensor Shield v5.0 installed. I'm running the basic publish and subscribe tutorial from rosserial:
http://wiki.ros.org/rosserial_arduino...
http://wiki.ros.org/rosserial_arduino...

When using USB shown as dev/ttyACM0, things are doing well.

Then, I'm trying to connect with HC-05 bluetooth module. First I connect it with command:

sudo rfcomm connect /dev/rfcomm0 00:06:71:00:3E:87 1

And the

Then launching rosserial as before with additional argument :

rosrun rosserial_python serial_node.py _port:=/dev/rfcomm0 _baud:=9600

With the tutorial code on the car:

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

ros::NodeHandle  nh;

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[13] = "hello world!";

void setup()
{
  nh.getHardware()->setBaud(9600);
  nh.initNode();
  nh.advertise(chatter);
}

void loop()
{
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(1000);
}

The terminal become a waterfall of running warning:

[INFO] [WallTime: 1410329846.797489] ROS Serial Python Node
[INFO] [WallTime: 1410329846.814548] Connecting to /dev/rfcomm0 at 9600 baud
[WARN] [WallTime: 1410329849.792440] Serial Port read returned short (expected 72 bytes, received 8 instead).   
[WARN] [WallTime: 1410329849.793548] Serial Port read failure: 
[INFO] [WallTime: 1410329849.794408] Packet Failed :  Failed to read msg data
[INFO] [WallTime: 1410329849.795036] msg len is 8
[WARN] [WallTime: 1410329850.814268] Serial Port read returned short (expected 16 bytes, received 13 instead).
[WARN] [WallTime: 1410329850.815325] Serial Port read failure: 
[INFO] [WallTime: 1410329850.816327] Packet Failed :  Failed to read msg data
[INFO] [WallTime: 1410329850.816984] msg len is 8

For most of the time its complaining about expected 72 bytes.

And thetopic,

rostopic info chatter

will return result (hello world!) quite randomly (it correctly shows with 1 Hz when using USB)

I've done another experiment on subscribe function. Arduino Car subscribe to std_msgs/Empty and topic is published by

rostopic pub toggle_led std_msgs/Empty --rate=1

The result is similar: some of the command can arrived (by moving the sonar servo) but quite randomly, and sometimes move more then 1 time in 1 second (published in 1Hz).

I've tried to read the source but still couldn't locate the problem.

Any help or suggestion are very welcome, thanks.

edit: It truns out it is the problem of baudrate of my bluetooth module! The chip (YFRobot) is a china made cheap one and not is a real HC-06 or any official supported chip. The common method of setting baudrate in a console just won't work. There is something like a single post in some unkown chinese forum that provides the datasheet (Luckily I can read simplified Chinese ^^). After a weird setup process, it's fine now, except that the module just won't work beyond exceed certain rate (57600 I think).

edit retag flag offensive close merge delete

Comments

ahendrix hello. I've never set the baud rate other then nh.getHardware()->setBaud() in bluetooth module. But if the baud rate is wrong, shouldn't it be completely unable to communicate? Using Arduino IDE with it's serial monitor and function like Serial.begin/Serial.write have no problem at all.

EwingKang gravatar image EwingKang  ( 2014-09-10 02:59:38 -0500 )edit

Most bluetooth modules have a UART buad rate that cannot be set through normal software. They usually have some sort of AT command set for modifying the baud rate.

ahendrix gravatar image ahendrix  ( 2014-09-10 03:19:20 -0500 )edit

Since the arduino serial console and Serial.write work over bluetooth, that means that the baud rate setting you're using matches the bluetooth module's setting, and it means that the problem is elsewhere.

ahendrix gravatar image ahendrix  ( 2014-09-10 03:20:29 -0500 )edit

Mmmmm ahendrix thank you. hope this can be fix. I'll keep trying.

EwingKang gravatar image EwingKang  ( 2014-09-10 03:38:32 -0500 )edit

@EwingKang I suggest you re-post the solution as an answer and select it as the right-answer so that others can tell this question has an answer.

130s gravatar image 130s  ( 2015-03-23 00:36:29 -0500 )edit

@130s OK, I see. I'm not sure whether if it is okay to do so here at ros answers. Some of the Q&A site forbid self-answering the question. Anyway, thanks.

edit: I see the line " you are encourage to answer you own...." when I editing my answer ^_^

EwingKang gravatar image EwingKang  ( 2015-03-23 21:20:29 -0500 )edit

3 Answers

Sort by » oldest newest most voted
1

answered 2015-03-23 21:44:08 -0500

EwingKang gravatar image

updated 2015-03-23 21:45:54 -0500

It truns out it is the problem of baudrate of my bluetooth module! The chip (named YFRobot HC-05) is a china made cheap one and not is a real HC-06 or any official supported chip. The common procedure of setting baudrate in a console just won't work. Finally There is something like a single post in some unkown chinese forum that provides the datasheet (Luckily I can read simplified Chinese ^^). http://www.yfrobot.com/forum.php?mod=...

You have to:

  1. connect PIN SET to 5V
  2. power up
  3. set up some kind of terminal that maps input 'Enter' to '\r\n' (carriage return and new line?). I think this is different from some of the board.
  4. use AT command to change the settings.
    AT+BAUD1---1200
    AT+BAUD2---2400
    AT+BAUD3---4800
    AT+BAUD4---9600(模塊出廠設置是9600頻率)
    AT+BAUD5--19200
    AT+BAUD6--38400
    AT+BAUD7--57600
    AT+BAUD8--115200
    AT+BAUD9--230400
    AT+BAUDA--460800
    AT+BAUDB--921600
    AT+BAUDC-1382400

But baud rate higher then 57600 is not usable on my module. Hope it helps someone.

edit flag offensive delete link more
1

answered 2014-09-10 02:44:51 -0500

ahendrix gravatar image

Are you sure the baud rate in the bluetooth module's firmware is set correctly? Does the serial over bluetooth work if you load a non-ROS sketch on your arduino?

edit flag offensive delete link more
0

answered 2015-06-02 12:25:35 -0500

I changed the timeout from 5 to 10 in Serialclient.py. This seems to work for me, though not 100 percent.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-09-10 02:28:17 -0500

Seen: 6,747 times

Last updated: Jun 02 '15