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_SERVICE_ApplyJointEffort_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_ApplyJointEffort_h
garyservin 0:fd24f7ca9688 3 #include <stdint.h>
garyservin 0:fd24f7ca9688 4 #include <string.h>
garyservin 0:fd24f7ca9688 5 #include <stdlib.h>
garyservin 0:fd24f7ca9688 6 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 7 #include "ros/duration.h"
garyservin 0:fd24f7ca9688 8 #include "ros/time.h"
garyservin 0:fd24f7ca9688 9
garyservin 0:fd24f7ca9688 10 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 static const char APPLYJOINTEFFORT[] = "gazebo_msgs/ApplyJointEffort";
garyservin 0:fd24f7ca9688 14
garyservin 0:fd24f7ca9688 15 class ApplyJointEffortRequest : public ros::Msg
garyservin 0:fd24f7ca9688 16 {
garyservin 0:fd24f7ca9688 17 public:
garyservin 0:fd24f7ca9688 18 const char* joint_name;
garyservin 0:fd24f7ca9688 19 double effort;
garyservin 0:fd24f7ca9688 20 ros::Time start_time;
garyservin 0:fd24f7ca9688 21 ros::Duration duration;
garyservin 0:fd24f7ca9688 22
garyservin 0:fd24f7ca9688 23 ApplyJointEffortRequest():
garyservin 0:fd24f7ca9688 24 joint_name(""),
garyservin 0:fd24f7ca9688 25 effort(0),
garyservin 0:fd24f7ca9688 26 start_time(),
garyservin 0:fd24f7ca9688 27 duration()
garyservin 0:fd24f7ca9688 28 {
garyservin 0:fd24f7ca9688 29 }
garyservin 0:fd24f7ca9688 30
garyservin 0:fd24f7ca9688 31 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 32 {
garyservin 0:fd24f7ca9688 33 int offset = 0;
garyservin 0:fd24f7ca9688 34 uint32_t length_joint_name = strlen(this->joint_name);
garyservin 0:fd24f7ca9688 35 memcpy(outbuffer + offset, &length_joint_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 36 offset += 4;
garyservin 0:fd24f7ca9688 37 memcpy(outbuffer + offset, this->joint_name, length_joint_name);
garyservin 0:fd24f7ca9688 38 offset += length_joint_name;
garyservin 0:fd24f7ca9688 39 union {
garyservin 0:fd24f7ca9688 40 double real;
garyservin 0:fd24f7ca9688 41 uint64_t base;
garyservin 0:fd24f7ca9688 42 } u_effort;
garyservin 0:fd24f7ca9688 43 u_effort.real = this->effort;
garyservin 0:fd24f7ca9688 44 *(outbuffer + offset + 0) = (u_effort.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 45 *(outbuffer + offset + 1) = (u_effort.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 46 *(outbuffer + offset + 2) = (u_effort.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 47 *(outbuffer + offset + 3) = (u_effort.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 48 *(outbuffer + offset + 4) = (u_effort.base >> (8 * 4)) & 0xFF;
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset + 5) = (u_effort.base >> (8 * 5)) & 0xFF;
garyservin 0:fd24f7ca9688 50 *(outbuffer + offset + 6) = (u_effort.base >> (8 * 6)) & 0xFF;
garyservin 0:fd24f7ca9688 51 *(outbuffer + offset + 7) = (u_effort.base >> (8 * 7)) & 0xFF;
garyservin 0:fd24f7ca9688 52 offset += sizeof(this->effort);
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 57 offset += sizeof(this->start_time.sec);
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 59 *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 60 *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 61 *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 62 offset += sizeof(this->start_time.nsec);
garyservin 0:fd24f7ca9688 63 *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 64 *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 65 *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 67 offset += sizeof(this->duration.sec);
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 70 *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 71 *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 72 offset += sizeof(this->duration.nsec);
garyservin 0:fd24f7ca9688 73 return offset;
garyservin 0:fd24f7ca9688 74 }
garyservin 0:fd24f7ca9688 75
garyservin 0:fd24f7ca9688 76 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 77 {
garyservin 0:fd24f7ca9688 78 int offset = 0;
garyservin 0:fd24f7ca9688 79 uint32_t length_joint_name;
garyservin 0:fd24f7ca9688 80 memcpy(&length_joint_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 81 offset += 4;
garyservin 0:fd24f7ca9688 82 for(unsigned int k= offset; k< offset+length_joint_name; ++k){
garyservin 0:fd24f7ca9688 83 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 84 }
garyservin 0:fd24f7ca9688 85 inbuffer[offset+length_joint_name-1]=0;
garyservin 0:fd24f7ca9688 86 this->joint_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 87 offset += length_joint_name;
garyservin 0:fd24f7ca9688 88 union {
garyservin 0:fd24f7ca9688 89 double real;
garyservin 0:fd24f7ca9688 90 uint64_t base;
garyservin 0:fd24f7ca9688 91 } u_effort;
garyservin 0:fd24f7ca9688 92 u_effort.base = 0;
garyservin 0:fd24f7ca9688 93 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 94 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 95 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 96 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 97 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:fd24f7ca9688 98 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:fd24f7ca9688 99 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:fd24f7ca9688 100 u_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:fd24f7ca9688 101 this->effort = u_effort.real;
garyservin 0:fd24f7ca9688 102 offset += sizeof(this->effort);
garyservin 0:fd24f7ca9688 103 this->start_time.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 104 this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 105 this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 106 this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 107 offset += sizeof(this->start_time.sec);
garyservin 0:fd24f7ca9688 108 this->start_time.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 109 this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 110 this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 111 this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 112 offset += sizeof(this->start_time.nsec);
garyservin 0:fd24f7ca9688 113 this->duration.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 114 this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 115 this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 116 this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 117 offset += sizeof(this->duration.sec);
garyservin 0:fd24f7ca9688 118 this->duration.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 119 this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 120 this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 121 this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 122 offset += sizeof(this->duration.nsec);
garyservin 0:fd24f7ca9688 123 return offset;
garyservin 0:fd24f7ca9688 124 }
garyservin 0:fd24f7ca9688 125
garyservin 0:fd24f7ca9688 126 const char * getType(){ return APPLYJOINTEFFORT; };
garyservin 0:fd24f7ca9688 127 const char * getMD5(){ return "2c3396ab9af67a509ecd2167a8fe41a2"; };
garyservin 0:fd24f7ca9688 128
garyservin 0:fd24f7ca9688 129 };
garyservin 0:fd24f7ca9688 130
garyservin 0:fd24f7ca9688 131 class ApplyJointEffortResponse : public ros::Msg
garyservin 0:fd24f7ca9688 132 {
garyservin 0:fd24f7ca9688 133 public:
garyservin 0:fd24f7ca9688 134 bool success;
garyservin 0:fd24f7ca9688 135 const char* status_message;
garyservin 0:fd24f7ca9688 136
garyservin 0:fd24f7ca9688 137 ApplyJointEffortResponse():
garyservin 0:fd24f7ca9688 138 success(0),
garyservin 0:fd24f7ca9688 139 status_message("")
garyservin 0:fd24f7ca9688 140 {
garyservin 0:fd24f7ca9688 141 }
garyservin 0:fd24f7ca9688 142
garyservin 0:fd24f7ca9688 143 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 144 {
garyservin 0:fd24f7ca9688 145 int offset = 0;
garyservin 0:fd24f7ca9688 146 union {
garyservin 0:fd24f7ca9688 147 bool real;
garyservin 0:fd24f7ca9688 148 uint8_t base;
garyservin 0:fd24f7ca9688 149 } u_success;
garyservin 0:fd24f7ca9688 150 u_success.real = this->success;
garyservin 0:fd24f7ca9688 151 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 152 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 153 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:fd24f7ca9688 154 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 155 offset += 4;
garyservin 0:fd24f7ca9688 156 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:fd24f7ca9688 157 offset += length_status_message;
garyservin 0:fd24f7ca9688 158 return offset;
garyservin 0:fd24f7ca9688 159 }
garyservin 0:fd24f7ca9688 160
garyservin 0:fd24f7ca9688 161 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 162 {
garyservin 0:fd24f7ca9688 163 int offset = 0;
garyservin 0:fd24f7ca9688 164 union {
garyservin 0:fd24f7ca9688 165 bool real;
garyservin 0:fd24f7ca9688 166 uint8_t base;
garyservin 0:fd24f7ca9688 167 } u_success;
garyservin 0:fd24f7ca9688 168 u_success.base = 0;
garyservin 0:fd24f7ca9688 169 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 170 this->success = u_success.real;
garyservin 0:fd24f7ca9688 171 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 172 uint32_t length_status_message;
garyservin 0:fd24f7ca9688 173 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 174 offset += 4;
garyservin 0:fd24f7ca9688 175 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:fd24f7ca9688 176 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 177 }
garyservin 0:fd24f7ca9688 178 inbuffer[offset+length_status_message-1]=0;
garyservin 0:fd24f7ca9688 179 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 180 offset += length_status_message;
garyservin 0:fd24f7ca9688 181 return offset;
garyservin 0:fd24f7ca9688 182 }
garyservin 0:fd24f7ca9688 183
garyservin 0:fd24f7ca9688 184 const char * getType(){ return APPLYJOINTEFFORT; };
garyservin 0:fd24f7ca9688 185 const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
garyservin 0:fd24f7ca9688 186
garyservin 0:fd24f7ca9688 187 };
garyservin 0:fd24f7ca9688 188
garyservin 0:fd24f7ca9688 189 class ApplyJointEffort {
garyservin 0:fd24f7ca9688 190 public:
garyservin 0:fd24f7ca9688 191 typedef ApplyJointEffortRequest Request;
garyservin 0:fd24f7ca9688 192 typedef ApplyJointEffortResponse Response;
garyservin 0:fd24f7ca9688 193 };
garyservin 0:fd24f7ca9688 194
garyservin 0:fd24f7ca9688 195 }
garyservin 0:fd24f7ca9688 196 #endif