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

Revision history [back]

click to hide/show revision 1
initial version

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-tasking-the-arduino-part-1/using-millis-for-timing).

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.