publishing before configure when using rosserial

asked 2014-04-08 21:58:45 -0500

Maya gravatar image

updated 2014-04-09 19:54:31 -0500

Hellow all,

I'm trying to use rosserial with an Arduino UNO (or Duemilanove I have the sme problem with both of them) to retrieve informaion given by an IMU.

First I increased the message buffer size like this :

namespace ros
{
#if defined(__AVR_ATmega8__) || defined(__AVR_ATmega168__)
  /* downsize our buffers */
  typedef NodeHandle_<ArduinoHardware, 6, 6, 150, 150> NodeHandle;

#elif defined(__AVR_ATmega328P__)
//  typedef NodeHandle_<ArduinoHardware, 25, 25, 280, 280> NodeHandle;
  typedef NodeHandle_<ArduinoHardware, 12, 12, 512, 512> NodeHandle;

#else

  typedef NodeHandle_<ArduinoHardware> NodeHandle;

#endif   
}

in ros.h in ros_lib and in the rosserial_arduino folder. This is because at first I had an error telling me the buffer size was to small.

Then I'm trying to publish a sensor_msgs::Imu through a publisher but It always fail. Here is the error message I have :

 ros@ros-K56CM:~$ rosrun rosserial_python serial_node.py /dev/ttyUSB0
[INFO] [WallTime: 1397029727.199687] ROS Serial Python Node
[INFO] [WallTime: 1397029727.213908] Connecting to /dev/ttyUSB0 at 57600 baud
[ERROR] [WallTime: 1397029729.700241] Tried to publish before configured, topic id 30
[ERROR] [WallTime: 1397029744.688688] Lost sync with device, restarting...
[ERROR] [WallTime: 1397029745.117519] Tried to publish before configured, topic id 30

And then the arduino freeze. If I start the restart it, it runs again and freeze when serial_node.py asked for the publisher. I know it freeze because I make a led blink all the time and it stop blinking after the first error message. Here is my code :

ros::NodeHandle  nh;

sensor_msgs::Imu imu_msg;
ros::Publisher pub_imu( "/imu", &imu_msg);
char frameid[] = "/imu";
#define PIN  13
int flag;
void setup() {  
  //Serial.begin(57600);

  nh.initNode();
  nh.advertise(pub_imu);
  imu_msg.header.frame_id =  frameid;
  imu_msg.header.stamp=nh.now();

  pinMode(PIN,OUTPUT);
  flag=0;

}

void loop() {

  blinking();

  delay(1000);
  writeData();
  pub_imu.publish(&imu_msg);
  nh.spinOnce();
}

I'm not even doing any operation nor anything complexe so I'm really lost at what is my problem :S. Furthermore, everything work fine with the ultrasonic example...

Any help will be appreciated. Thank you.

edit retag flag offensive close merge delete

Comments

Have you solved your problem? I know that a lot of time has passed, but I'm getting problems with rosserial on an arduino meant to retrieve informaion given by an IMU, that is, a problem pretty similar to yours.

nvoltex gravatar image nvoltex  ( 2015-01-31 16:20:22 -0500 )edit

Wow that was a long time ago. I don't think I solved this problem. It was not essential to my project so I moved on sorry :S

Maya gravatar image Maya  ( 2015-02-03 04:44:04 -0500 )edit