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

Is that problem of running out of SRAM of Arduino UNO

asked 2015-06-10 12:27:56 -0500

crazymumu gravatar image

updated 2015-06-10 15:43:02 -0500

I use ROS in virtualbox which install Ubuntun

#include <ros.h>
    #include <std_msgs/Float32.h>
    #define DIR_R  7             //Right motor Direction control line
    #define DIR_L  8             //Left motor Direction control line
    #define PWM_R  9             //Right motor PWM control line
    #define PWM_L  10            //Left motor PWM control line
    #define LED    13
    #define SPEED  45
    ros::NodeHandle nh;

    int rightSpeed, leftSpeed;
    double relative_angle;

    void messageCb(const std_msgs::Float32& str){

            //int rightSpeed, leftSpeed;

            if(str.data == -1){                    //no free-space front Zumo robot, rotate to find another one
                     rightSpeed =SPEED;
                     leftSpeed  =SPEED;
                     rotatePort(rightSpeed, leftSpeed, 500, 1);
                     searchPort(200,200);
            }
            else
            {
                relative_angle=abs(90.0-str.data);

                if (relative_angle <= 2.0)         //optional direction in front of Zumo robot
                {
                     rightSpeed =SPEED;
                     leftSpeed  =SPEED;
                     forwardPort(rightSpeed, leftSpeed, 500, 1);
                }
                else
                {
                     if (str.data <90.0)
                     {
                         rightSpeed =SPEED - relative_angle/90.0*SPEED;
                         leftSpeed  =SPEED + relative_angle/90.0*SPEED;
                         turnPort(rightSpeed, leftSpeed, 500, 1);
                     }
                     else
                     {
                         rightSpeed =SPEED + relative_angle/90.0*SPEED;
                         leftSpeed  =SPEED - relative_angle/90.0*SPEED;
                         turnPort(rightSpeed, leftSpeed, 500, 1);                     
                     }     
                }


            }
    }

    ros::Subscriber<std_msgs::Float32> sub("/space1/move_zumo", &messageCb);

    void setup(){
      pinMode(LED, OUTPUT);
      pinMode(DIR_R, OUTPUT);
      pinMode(DIR_L, OUTPUT);
      pinMode(PWM_R, OUTPUT);
      pinMode(PWM_L, OUTPUT);      
      nh.initNode();
      nh.subscribe(sub);
    }

    void loop(){
      nh.spinOnce();
      delay(50);
    }

    void rotatePort  (int rs, int ls, int T1, int T2)
    {
        digitalWrite(DIR_R, LOW);
        digitalWrite(DIR_L, HIGH);
        analogWrite(PWM_R, rs);
        analogWrite(PWM_L, ls);
        delay(T1);
        analogWrite(PWM_R, 0);
        analogWrite(PWM_L, 0);
        delay(T2);
    }

    void forwardPort (int rs, int ls, int T1, int T2)
    {
        digitalWrite(DIR_R, LOW);
        digitalWrite(DIR_L, LOW);
        analogWrite(PWM_R, rs);
        analogWrite(PWM_L, ls);
        delay(T1);
        analogWrite(PWM_R, 0);
        analogWrite(PWM_L, 0);
        delay(T2);   
    }

    void turnPort(int rs, int ls, int T1, int T2)
    {
        digitalWrite(DIR_R, LOW);
        digitalWrite(DIR_L, LOW);
        analogWrite(PWM_R, rs);
        analogWrite(PWM_L, ls);
        delay(T1);
        analogWrite(PWM_R, 0);
        analogWrite(PWM_L, 0);
        delay(T2);      
    }

    void searchPort(int T1, int T2)
    {
        digitalWrite(LED,HIGH);
        delay(T1);
        digitalWrite(LED,LOW);
        delay(T2); 
    }

Here is my serial node in launch file.

    <node
        pkg = "rosserial_python"
        type = "serial_node.py"
        name = "serial_node"
        >
        <param name = "port" value = "/dev/ttyACM1"/>
        <param name = "baud" value ="57600" />
    </node>

Here is my arduino code with a loop 20 hz, and the ros node publish to arduino is 10 hz. Just publish float data not string. When I run, first it's ok but later it said

> [ERROR] [WallTime: 1433956349.977347]
> Lost sync with device, restarting...

When i change ros node publish rate to 1 hz, it works fine.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-06-10 14:38:04 -0500

jseal gravatar image

updated 2015-06-11 09:42:23 -0500

I think your problem is your delaying 500 millisecond on your port functions. So your code is stuck in the messageCb function and doesn't have a chance to spin until the callback finishing, thus losing sync.

Also your Arduino loop is at 20 hz instead of 50 hz.

Updated:

You have to get rid of the 500 millisecond delays (0.5 seconds), to run something at 10,20 or 50 hz. The Uno is single core, so your messageCb has to be executed and finished in < 100 millisecond to run something at 10 hz. So ros can get back to looking for published message. If 0.5 second goes by before ros can start looking for published message it will be unable to keep up at 10 hz.

Since I don't know all your details or exactly what your trying to do, there might be a better way of implementing this. Here's an idea for removing the long delays, there might be some additional bookkeeping needed in you messageCb function.

int motorEnabledFlag = 0;  
unsigned long cutoffMillis;

//...
//...


void loop()
{
  nh.spinOnce();

  if(motorEnabledFlag)
  {
     if(millis()  >= cutoffMillis) 
     { //500 milliseconds has passed
       analogWrite(PWM_R, 0);
       analogWrite(PWM_L, 0);
       motorEnabledFlag = 0;
     }   
  }
  delay(50);//Might be more effiecent to just delay 1 and control the frequency
  //loop in the publisher
}

void forwardPort (int rs, int ls)
{
  digitalWrite(DIR_R, LOW);
  digitalWrite(DIR_L, LOW);
  analogWrite(PWM_R, rs);
  analogWrite(PWM_L, ls);
  motorEnabledFlag = 1;
  cutoffMillis = millis() + 500;//Probably should use a ros Time function
  //delay(T1); -- If T1 = 500, this causes a 0.5 second delay where 
  //nothing else happens so you can't run a publisher at 10 hz.  
}

//...
//...
edit flag offensive delete link more

Comments

yes, it's 20 HZ. Could you tell me how to change the loop rate, increase or decrease. Thanks

crazymumu gravatar image crazymumu  ( 2015-06-10 15:03:10 -0500 )edit

delay(20) is what you want. 20 milliseconds or 0.02 seconds. 1/0.02 = 50 hz

jseal gravatar image jseal  ( 2015-06-10 16:37:08 -0500 )edit

20 HZ didn't work neither, do you other suggestions? Thanks

crazymumu gravatar image crazymumu  ( 2015-06-10 21:05:02 -0500 )edit

Read the first part of my answer again, Your problem is delay(T1) where T1 = 500. It's blocking for 500 milliseconds. I'm not sure what your trying to do, but if you need a 500 millisecond pulse, you might want to start a timer in your port function skip the delay and in your loop once the timer

jseal gravatar image jseal  ( 2015-06-10 21:16:32 -0500 )edit

reaches 500 millisecond it sets the pulse back low.

jseal gravatar image jseal  ( 2015-06-10 21:20:22 -0500 )edit

Let me know if you need me to explain further.

jseal gravatar image jseal  ( 2015-06-10 21:30:35 -0500 )edit

I though delay(T1) is the time to running motor. delay(50) in the loop is time to receive command from ros, which is an angle . then depend on the angle to let motors move.
could you add some code to show your answer. Thanks so much. I am new to arduino coding.

crazymumu gravatar image crazymumu  ( 2015-06-11 01:47:39 -0500 )edit

The delay function by itself does nothing for that many milliseconds. I've updated my answer see if it helps.

jseal gravatar image jseal  ( 2015-06-11 09:31:33 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-06-10 12:27:56 -0500

Seen: 598 times

Last updated: Jun 11 '15