Robotics StackExchange | Archived questions

Arduino multiple callback error

Hello everyone, thanks for the attention! I am using Ros Kinetic on Ubuntu Mate as OS, running on a Raspbery Pi 3 I am trying to use an Arduino Mega 2560 to do a few things in my robot. Control my Stepper Motors, publish raw IMU data and publish encoder readings.

The codes can be located here: https://github.com/renanmb/Ros_arduino

The Problem is:

When I use Arduino with only one type of message it works. However, when it runs different callbacks and publishers of different types, for example: Boolean, Int32 and Float 32. It does not work.

I receive the following message on my Terminal:

[ERROR] [ 1433855869.447165] Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino

In my Github Repository called Ros_arduino:

The codes that do not work

ros_surp.ino (lowercase, the upper case one is missing stuff)

ROS_PWM.ino

The codes that do work

IMUROStest2.ino

chapter7_book.ino

chapter7bookblink_and ......

I thought it was the following erros:

So what should I do to fix it?

I want to know if there is a way to use my Arduino to control multiple actuators and publish IMU and encoder data. If not I want to know if there is any board that I could use for that. I am considering as a last case scenario to use multiple arduinos, because it is an Ugly solution and takes a lot of space.

I am using the Arduino because of the AVR micro controller that is easier and generates a much better PWM signal than ARM based micro controller.

My code: ros_surp.ino

gives me

[ERROR] [ 1433855869.447165] Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino

#include <Wire.h>
#include <ros.h>

#include <Adafruit_Sensor.h>
#include <Adafruit_LSM303.h>
#include <Adafruit_LSM303_U.h>

#include <std_msgs/Float32.h>
#include <std_msgs/Int32.h>
#include <std_msgs/Bool.h>

#include <Encoder.h> //encoder library - http://www.pjrc.com/teensy/td_libs_Encoder.html

#include <PWM.h> //PWM library for controlling the steppers

/* Assign a unique ID to the sensors */
Adafruit_LSM303_Accel_Unified accel = Adafruit_LSM303_Accel_Unified(30301);
//******** add later gyroscope and magnet sensor for more complex positioning


//  Both pins must have interrupt capability
Encoder myEnc(2,3);

//Motor pins
//use pin 11 on the Mega instead, otherwise there is a frequency cap at 31 Hz
const int step_pin1 = 11;     // the pin that define the steps
const int dir_pin1 = 22;      // the dir pin
const int step_pin2 = 12;     // the pin that define the steps
const int dir_pin2 = 24;
int32_t frequency1 = 0; //frequency (in Hz)
int32_t frequency2 = 0; //frequency (in Hz)

ros::NodeHandle nh;
std_msgs::Float32 velLinear_x;
std_msgs::Float32 velAngular_z;
std_msgs::Int32 encoder;
std_msgs::Bool motor1_dir;
std_msgs::Bool motor2_dir;
std_msgs::Float32 motor1_cmd;
std_msgs::Float32 motor2_cmd;

ros::Publisher velLinear_x_pub("velLinear_x" , &velLinear_x);
ros::Publisher velAngular_z_pub("velAngular_z" , &velAngular_z);
ros::Publisher encoder_pub("encoder" , &encoder);

void initSensors(){
   if(!accel.begin())
  {
    /* There was a problem detecting the LSM303 ... check your connections */
    Serial.println(F("Ooops, no LSM303 detected ... Check your wiring!"));
    while(1);
  }
}

void motor1_cmd_callback(const std_msgs::Float32& motor1_cmd){
  frequency1 = (int)motor1_cmd.data;  
}

void motor2_cmd_callback(const std_msgs::Float32& motor2_cmd){
  frequency2 = (int)motor2_cmd.data;
}

void motor1_dir_callback(const std_msgs::Bool& motor1_dir){
  if(motor1_dir.data == true){
    digitalWrite(dir_pin1, HIGH);
  }
  else{
    digitalWrite(dir_pin1, LOW);
  }
}

void motor2_dir_callback(const std_msgs::Bool& motor2_dir){
  if(motor2_dir.data == true){
    digitalWrite(dir_pin2, HIGH);
  }
  else{
    digitalWrite(dir_pin2, LOW);
  }
}

 ros::Subscriber<std_msgs::Float32> sub1("motor1_cmd", &motor1_cmd_callback );
 ros::Subscriber<std_msgs::Float32> sub2("motor2_cmd", &motor2_cmd_callback );
 ros::Subscriber<std_msgs::Bool> sub3("motor1_dir", &motor1_cmd_callback );
 ros::Subscriber<std_msgs::Bool> sub4("motor2_dir", &motor2_cmd_callback );

void setup(void){ /* this is the same as void setup() but for older C and C++ */
  //Serial.begin(1000000);
  //initialize all timers except for 0, to save time keeping functions
  InitTimersSafe(); 

  nh.initNode();
  nh.advertise(velLinear_x_pub);
  nh.advertise(velAngular_z_pub);
  nh.advertise(encoder_pub);
  nh.subscribe(sub1);
  nh.subscribe(sub2);
  nh.subscribe(sub3);
  nh.subscribe(sub4);

  // =======================================================================================
  /* ================ PWM Function  ======================================================= */

  //PWM to the motors
  pinMode(step_pin1, OUTPUT);
  pinMode(dir_pin1, OUTPUT);
  SetPinFrequency(step_pin1, frequency1); //change for the callback function of motor1_cmd
  pinMode(step_pin2, OUTPUT);
  pinMode(dir_pin2, OUTPUT);
  SetPinFrequency(step_pin2, frequency2); //change for the callback function of motor2_cmd

  while(true){
    //setting the duty to 50% with the highest possible resolution that 
    //can be applied to the timer (up to 16 bit). 1/2 of 65536 is 32768.
    pwmWriteHR(step_pin1, 32768);
    pwmWriteHR(step_pin2, 32768);
  }

   //initialize the sensor and its bandwidth here
   initSensors();

}

long oldPosition  = -999;

void loop(void){ /* this is the same as void loop() but for older C and C++ */

  /*create here the variables to store de data received from the sensor.*/
  /* Objects */
  sensors_event_t accel_event;

  /* Read the accelerometer */
  accel.getEvent(&accel_event);

  /* How do I insert in the right units ? */
  velLinear_x.data = accel_event.acceleration.x ;
  velAngular_z.data = accel_event.acceleration.y ;

  /* Encoder reading - long in arduino is the same as int32
     This code gives a int32 number that can be copared to get speed
     myEnc.*/
  long newPosition = myEnc.read();
  if (newPosition != oldPosition) {
    oldPosition = newPosition;
    encoder.data = newPosition;
  }

  velLinear_x_pub.publish(&velLinear_x);
  velAngular_z_pub.publish(&velAngular_z);
  encoder_pub.publish(&encoder);

  nh.spinOnce();
  delay(10);
}

Same error message for this code:

ROS_PWM.ino

#include <Wire.h>
#include <ros.h>

#include <std_msgs/Float32.h>
#include <std_msgs/Int32.h>
#include <std_msgs/Bool.h>

#include <PWM.h> //PWM library for controlling the steppers

//Motor pins
//use pin 11 on the Mega instead, otherwise there is a frequency cap at 31 Hz
const int step_pin1 = 11;     // the pin that define the steps
const int dir_pin1 = 22;      // the dir pin
const int step_pin2 = 12;     // the pin that define the steps
const int dir_pin2 = 24;
int32_t frequency1 = 0; //frequency (in Hz)
int32_t frequency2 = 0; //frequency (in Hz)

ros::NodeHandle nh;
std_msgs::Bool motor1_dir;
std_msgs::Bool motor2_dir;
std_msgs::Float32 motor1_cmd;
std_msgs::Float32 motor2_cmd;

//Motor_cmd Subscriber
void motor1_cmd_callback(const std_msgs::Float32& motor1_cmd){
  frequency1 = (int)motor1_cmd.data;  
}

void motor2_cmd_callback(const std_msgs::Float32& motor2_cmd){
  frequency2 = (int)motor2_cmd.data;
}

//Motor_dir Subscriber
void motor1_dir_callback(const std_msgs::Bool& motor1_dir){
  if(motor1_dir.data == true){
    digitalWrite(dir_pin1, HIGH);
  }
  else{
    digitalWrite(dir_pin1, LOW);
  }
}

void motor2_dir_callback(const std_msgs::Bool& motor2_dir){
  if(motor2_dir.data == true){
    digitalWrite(dir_pin2, HIGH);
  }
  else{
    digitalWrite(dir_pin2, LOW);
  }
}

 ros::Subscriber<std_msgs::Float32> sub1("motor1_cmd", &motor1_cmd_callback );
 ros::Subscriber<std_msgs::Float32> sub2("motor2_cmd", &motor2_cmd_callback );
 ros::Subscriber<std_msgs::Bool> sub3("motor1_dir", &motor1_cmd_callback );
 ros::Subscriber<std_msgs::Bool> sub4("motor2_dir", &motor2_cmd_callback );

void setup(void){ /* this is the same as void setup() but for older C and C++ */
  //initialize all timers except for 0, to save time keeping functions
  InitTimersSafe(); 

 nh.initNode();
 nh.subscribe(sub1);
 nh.subscribe(sub2);
 nh.subscribe(sub3);
 nh.subscribe(sub4);

  // =======================================================================================
  /* ================ PWM Function  ======================================================= */

  //PWM to the motors
  pinMode(step_pin1, OUTPUT);
  pinMode(dir_pin1, OUTPUT);
  SetPinFrequency(step_pin1, frequency1); //change for the callback function of motor1_cmd
  pinMode(step_pin2, OUTPUT);
  pinMode(dir_pin2, OUTPUT);
  SetPinFrequency(step_pin2, frequency2); //change for the callback function of motor2_cmd

  while(true){
    //setting the duty to 50% with the highest possible resolution that 
    //can be applied to the timer (up to 16 bit). 1/2 of 65536 is 32768.
    pwmWriteHR(step_pin1, 32768);
    pwmWriteHR(step_pin2, 32768);
  }

}

void loop(void){ /* this is the same as void loop() but for older C and C++ */
  nh.spinOnce();
  delay(10);
}

Asked by renanmb on 2017-07-29 21:48:28 UTC

Comments

This question would be much more useful if the code that is giving you trouble is posted here instead of somewhere else. External webpages can become inaccessible or dead.

Asked by jayess on 2017-07-30 00:21:20 UTC

Did you set the proper permissions on the port?

Asked by jayess on 2017-07-30 00:32:28 UTC

Yes, and it work fine for other codes. Just when I try to run more than one subscriber/publisher , or both that it show me that error message.

Asked by renanmb on 2017-07-30 00:52:56 UTC

Why do you use while(true) in your setup function? I don't see how it would work very leave setup

Asked by allenh1 on 2017-07-30 17:14:54 UTC

The while(true) is for the PWM library. I possibly can change it, but it worked on the code without ros.

Asked by renanmb on 2017-07-30 19:27:09 UTC

While I don't have much experience with Arduino, it would seem that with that loop you will never leave the setup function.

Asked by jayess on 2017-07-30 19:56:20 UTC

But it leaves, because most of the code for the PWM is working with the registers, not always it is true it turns on and off. I dont know very well how that works too but it works. I have been thinking about using message_filters, I saw good results but I dont know how to use, not many tutorials.

Asked by renanmb on 2017-07-30 20:01:11 UTC

Message_filters , may solve the problem if it is merging all the message into just one subscriber. Because when I run just 1 subscriber it works. When I run multiple it does not work.

Asked by renanmb on 2017-07-30 20:03:01 UTC

Maybe the buffer is being over filled. Although, True is always True so if you're using it as a condition for a loop, then that loop will loop forever.

Asked by jayess on 2017-07-30 20:07:27 UTC

I solved my problem creating my own message, I may try also to create a service for my closed-loop-system. But the question stays. Why we can`t use multiple subscribers???? It would be much easier than create a huge msg or srv .

Asked by renanmb on 2017-07-31 02:24:11 UTC

You can definitely create multiple subscribers. I would move the contents of the loop into the loop function, as it's essentially performing the same task, right?

Asked by allenh1 on 2017-07-31 13:27:09 UTC

The while(True) is not necessary. I tested other codes and it worked fine. So please, could you make your modifications on ROS_PWM_test1.ino https://github.com/renanmb/Ros_arduino/blob/master/ROS_PWM_test1.ino As example, it is smaller and while(true) you can get ride of it if you want.

Asked by renanmb on 2017-07-31 14:12:21 UTC

buffer is not being overfilled, I made a code ROS_PWM_test3.ino on my github and it works when I pak everything in just one giant message.

Asked by renanmb on 2017-07-31 14:16:23 UTC

Answers