ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

ROSSerial_mbed for Indigo Distribution

The Robot Operating System (ROS) is a flexible framework for writing robot software. It is a collection of tools, libraries, and conventions that aim to simplify the task of creating complex and robust robot behavior across a wide variety of robotic platforms.

The rosserial_mbed package allows to write ROS nodes on any mbed enabled devices and have them connected to a running ROS system on your computer using the serial port.

Hello World (example publisher)

Import programrosserial_mbed_hello_world_publisher

rosserial_mbed Hello World

Running the Code

Now, launch the roscore in a new terminal window:

Quote:

$ roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

Quote:

$ rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, watch the greetings come in from your MBED by launching a new terminal window and entering :

Quote:

$ rostopic echo chatter

See Also

More examples

Blink

/*
 * rosserial Subscriber Example
 * Blinks an LED on callback
 */
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle nh;
DigitalOut myled(LED1);

void messageCb(const std_msgs::Empty& toggle_msg){
    myled = !myled;   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

int main() {
    nh.initNode();
    nh.subscribe(sub);

    while (1) {
        nh.spinOnce();
        wait_ms(1);
    }
}

Push

/*
 * Button Example for Rosserial
 */

#include "mbed.h"
#include <ros.h>
#include <std_msgs/Bool.h>

PinName button = p20;

ros::NodeHandle nh;

std_msgs::Bool pushed_msg;
ros::Publisher pub_button("pushed", &pushed_msg);

DigitalIn button_pin(button);
DigitalOut led_pin(LED1);

bool last_reading;
long last_debounce_time=0;
long debounce_delay=50;
bool published = true;

Timer t;
int main() {
    t.start();
    nh.initNode();
    nh.advertise(pub_button);

    //Enable the pullup resistor on the button
    button_pin.mode(PullUp);

    //The button is a normally button
    last_reading = ! button_pin;

    while (1) {
        bool reading = ! button_pin;

        if (last_reading!= reading) {
            last_debounce_time = t.read_ms();
            published = false;
        }

        //if the button value has not changed for the debounce delay, we know its stable
        if ( !published && (t.read_ms() - last_debounce_time)  > debounce_delay) {
            led_pin = reading;
            pushed_msg.data = reading;
            pub_button.publish(&pushed_msg);
            published = true;
        }

        last_reading = reading;

        nh.spinOnce();
    }
}
Committer:
garyservin
Date:
Thu Mar 31 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_control_msgs_FollowJointTrajectoryGoal_h
garyservin 0:fd24f7ca9688 2 #define _ROS_control_msgs_FollowJointTrajectoryGoal_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "trajectory_msgs/JointTrajectory.h"
garyservin 0:fd24f7ca9688 9 #include "control_msgs/JointTolerance.h"
garyservin 0:fd24f7ca9688 10 #include "ros/duration.h"
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 namespace control_msgs
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14
garyservin 0:fd24f7ca9688 15 class FollowJointTrajectoryGoal : public ros::Msg
garyservin 0:fd24f7ca9688 16 {
garyservin 0:fd24f7ca9688 17 public:
garyservin 0:fd24f7ca9688 18 trajectory_msgs::JointTrajectory trajectory;
garyservin 0:fd24f7ca9688 19 uint8_t path_tolerance_length;
garyservin 0:fd24f7ca9688 20 control_msgs::JointTolerance st_path_tolerance;
garyservin 0:fd24f7ca9688 21 control_msgs::JointTolerance * path_tolerance;
garyservin 0:fd24f7ca9688 22 uint8_t goal_tolerance_length;
garyservin 0:fd24f7ca9688 23 control_msgs::JointTolerance st_goal_tolerance;
garyservin 0:fd24f7ca9688 24 control_msgs::JointTolerance * goal_tolerance;
garyservin 0:fd24f7ca9688 25 ros::Duration goal_time_tolerance;
garyservin 0:fd24f7ca9688 26
garyservin 0:fd24f7ca9688 27 FollowJointTrajectoryGoal():
garyservin 0:fd24f7ca9688 28 trajectory(),
garyservin 0:fd24f7ca9688 29 path_tolerance_length(0), path_tolerance(NULL),
garyservin 0:fd24f7ca9688 30 goal_tolerance_length(0), goal_tolerance(NULL),
garyservin 0:fd24f7ca9688 31 goal_time_tolerance()
garyservin 0:fd24f7ca9688 32 {
garyservin 0:fd24f7ca9688 33 }
garyservin 0:fd24f7ca9688 34
garyservin 0:fd24f7ca9688 35 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 36 {
garyservin 0:fd24f7ca9688 37 int offset = 0;
garyservin 0:fd24f7ca9688 38 offset += this->trajectory.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 39 *(outbuffer + offset++) = path_tolerance_length;
garyservin 0:fd24f7ca9688 40 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 41 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 42 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 43 for( uint8_t i = 0; i < path_tolerance_length; i++){
garyservin 0:fd24f7ca9688 44 offset += this->path_tolerance[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 45 }
garyservin 0:fd24f7ca9688 46 *(outbuffer + offset++) = goal_tolerance_length;
garyservin 0:fd24f7ca9688 47 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 48 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 50 for( uint8_t i = 0; i < goal_tolerance_length; i++){
garyservin 0:fd24f7ca9688 51 offset += this->goal_tolerance[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 52 }
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset + 0) = (this->goal_time_tolerance.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset + 1) = (this->goal_time_tolerance.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset + 2) = (this->goal_time_tolerance.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset + 3) = (this->goal_time_tolerance.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 57 offset += sizeof(this->goal_time_tolerance.sec);
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset + 0) = (this->goal_time_tolerance.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 59 *(outbuffer + offset + 1) = (this->goal_time_tolerance.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 60 *(outbuffer + offset + 2) = (this->goal_time_tolerance.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 61 *(outbuffer + offset + 3) = (this->goal_time_tolerance.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 62 offset += sizeof(this->goal_time_tolerance.nsec);
garyservin 0:fd24f7ca9688 63 return offset;
garyservin 0:fd24f7ca9688 64 }
garyservin 0:fd24f7ca9688 65
garyservin 0:fd24f7ca9688 66 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 67 {
garyservin 0:fd24f7ca9688 68 int offset = 0;
garyservin 0:fd24f7ca9688 69 offset += this->trajectory.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 70 uint8_t path_tolerance_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 71 if(path_tolerance_lengthT > path_tolerance_length)
garyservin 0:fd24f7ca9688 72 this->path_tolerance = (control_msgs::JointTolerance*)realloc(this->path_tolerance, path_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
garyservin 0:fd24f7ca9688 73 offset += 3;
garyservin 0:fd24f7ca9688 74 path_tolerance_length = path_tolerance_lengthT;
garyservin 0:fd24f7ca9688 75 for( uint8_t i = 0; i < path_tolerance_length; i++){
garyservin 0:fd24f7ca9688 76 offset += this->st_path_tolerance.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 77 memcpy( &(this->path_tolerance[i]), &(this->st_path_tolerance), sizeof(control_msgs::JointTolerance));
garyservin 0:fd24f7ca9688 78 }
garyservin 0:fd24f7ca9688 79 uint8_t goal_tolerance_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 80 if(goal_tolerance_lengthT > goal_tolerance_length)
garyservin 0:fd24f7ca9688 81 this->goal_tolerance = (control_msgs::JointTolerance*)realloc(this->goal_tolerance, goal_tolerance_lengthT * sizeof(control_msgs::JointTolerance));
garyservin 0:fd24f7ca9688 82 offset += 3;
garyservin 0:fd24f7ca9688 83 goal_tolerance_length = goal_tolerance_lengthT;
garyservin 0:fd24f7ca9688 84 for( uint8_t i = 0; i < goal_tolerance_length; i++){
garyservin 0:fd24f7ca9688 85 offset += this->st_goal_tolerance.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 86 memcpy( &(this->goal_tolerance[i]), &(this->st_goal_tolerance), sizeof(control_msgs::JointTolerance));
garyservin 0:fd24f7ca9688 87 }
garyservin 0:fd24f7ca9688 88 this->goal_time_tolerance.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 89 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 90 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 91 this->goal_time_tolerance.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 92 offset += sizeof(this->goal_time_tolerance.sec);
garyservin 0:fd24f7ca9688 93 this->goal_time_tolerance.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 94 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 95 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 96 this->goal_time_tolerance.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 97 offset += sizeof(this->goal_time_tolerance.nsec);
garyservin 0:fd24f7ca9688 98 return offset;
garyservin 0:fd24f7ca9688 99 }
garyservin 0:fd24f7ca9688 100
garyservin 0:fd24f7ca9688 101 const char * getType(){ return "control_msgs/FollowJointTrajectoryGoal"; };
garyservin 0:fd24f7ca9688 102 const char * getMD5(){ return "69636787b6ecbde4d61d711979bc7ecb"; };
garyservin 0:fd24f7ca9688 103
garyservin 0:fd24f7ca9688 104 };
garyservin 0:fd24f7ca9688 105
garyservin 0:fd24f7ca9688 106 }
garyservin 0:fd24f7ca9688 107 #endif