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_SetModelConfiguration_h
garyservin 0:fd24f7ca9688 2 #define _ROS_SERVICE_SetModelConfiguration_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
garyservin 0:fd24f7ca9688 8 namespace gazebo_msgs
garyservin 0:fd24f7ca9688 9 {
garyservin 0:fd24f7ca9688 10
garyservin 0:fd24f7ca9688 11 static const char SETMODELCONFIGURATION[] = "gazebo_msgs/SetModelConfiguration";
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class SetModelConfigurationRequest : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 const char* model_name;
garyservin 0:fd24f7ca9688 17 const char* urdf_param_name;
garyservin 0:fd24f7ca9688 18 uint8_t joint_names_length;
garyservin 0:fd24f7ca9688 19 char* st_joint_names;
garyservin 0:fd24f7ca9688 20 char* * joint_names;
garyservin 0:fd24f7ca9688 21 uint8_t joint_positions_length;
garyservin 0:fd24f7ca9688 22 double st_joint_positions;
garyservin 0:fd24f7ca9688 23 double * joint_positions;
garyservin 0:fd24f7ca9688 24
garyservin 0:fd24f7ca9688 25 SetModelConfigurationRequest():
garyservin 0:fd24f7ca9688 26 model_name(""),
garyservin 0:fd24f7ca9688 27 urdf_param_name(""),
garyservin 0:fd24f7ca9688 28 joint_names_length(0), joint_names(NULL),
garyservin 0:fd24f7ca9688 29 joint_positions_length(0), joint_positions(NULL)
garyservin 0:fd24f7ca9688 30 {
garyservin 0:fd24f7ca9688 31 }
garyservin 0:fd24f7ca9688 32
garyservin 0:fd24f7ca9688 33 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 34 {
garyservin 0:fd24f7ca9688 35 int offset = 0;
garyservin 0:fd24f7ca9688 36 uint32_t length_model_name = strlen(this->model_name);
garyservin 0:fd24f7ca9688 37 memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 38 offset += 4;
garyservin 0:fd24f7ca9688 39 memcpy(outbuffer + offset, this->model_name, length_model_name);
garyservin 0:fd24f7ca9688 40 offset += length_model_name;
garyservin 0:fd24f7ca9688 41 uint32_t length_urdf_param_name = strlen(this->urdf_param_name);
garyservin 0:fd24f7ca9688 42 memcpy(outbuffer + offset, &length_urdf_param_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 43 offset += 4;
garyservin 0:fd24f7ca9688 44 memcpy(outbuffer + offset, this->urdf_param_name, length_urdf_param_name);
garyservin 0:fd24f7ca9688 45 offset += length_urdf_param_name;
garyservin 0:fd24f7ca9688 46 *(outbuffer + offset++) = joint_names_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 < joint_names_length; i++){
garyservin 0:fd24f7ca9688 51 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
garyservin 0:fd24f7ca9688 52 memcpy(outbuffer + offset, &length_joint_namesi, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 53 offset += 4;
garyservin 0:fd24f7ca9688 54 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
garyservin 0:fd24f7ca9688 55 offset += length_joint_namesi;
garyservin 0:fd24f7ca9688 56 }
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset++) = joint_positions_length;
garyservin 0:fd24f7ca9688 58 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 59 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 60 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 61 for( uint8_t i = 0; i < joint_positions_length; i++){
garyservin 0:fd24f7ca9688 62 union {
garyservin 0:fd24f7ca9688 63 double real;
garyservin 0:fd24f7ca9688 64 uint64_t base;
garyservin 0:fd24f7ca9688 65 } u_joint_positionsi;
garyservin 0:fd24f7ca9688 66 u_joint_positionsi.real = this->joint_positions[i];
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 0) = (u_joint_positionsi.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 1) = (u_joint_positionsi.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 2) = (u_joint_positionsi.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 70 *(outbuffer + offset + 3) = (u_joint_positionsi.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 71 *(outbuffer + offset + 4) = (u_joint_positionsi.base >> (8 * 4)) & 0xFF;
garyservin 0:fd24f7ca9688 72 *(outbuffer + offset + 5) = (u_joint_positionsi.base >> (8 * 5)) & 0xFF;
garyservin 0:fd24f7ca9688 73 *(outbuffer + offset + 6) = (u_joint_positionsi.base >> (8 * 6)) & 0xFF;
garyservin 0:fd24f7ca9688 74 *(outbuffer + offset + 7) = (u_joint_positionsi.base >> (8 * 7)) & 0xFF;
garyservin 0:fd24f7ca9688 75 offset += sizeof(this->joint_positions[i]);
garyservin 0:fd24f7ca9688 76 }
garyservin 0:fd24f7ca9688 77 return offset;
garyservin 0:fd24f7ca9688 78 }
garyservin 0:fd24f7ca9688 79
garyservin 0:fd24f7ca9688 80 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 81 {
garyservin 0:fd24f7ca9688 82 int offset = 0;
garyservin 0:fd24f7ca9688 83 uint32_t length_model_name;
garyservin 0:fd24f7ca9688 84 memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 85 offset += 4;
garyservin 0:fd24f7ca9688 86 for(unsigned int k= offset; k< offset+length_model_name; ++k){
garyservin 0:fd24f7ca9688 87 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 88 }
garyservin 0:fd24f7ca9688 89 inbuffer[offset+length_model_name-1]=0;
garyservin 0:fd24f7ca9688 90 this->model_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 91 offset += length_model_name;
garyservin 0:fd24f7ca9688 92 uint32_t length_urdf_param_name;
garyservin 0:fd24f7ca9688 93 memcpy(&length_urdf_param_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 94 offset += 4;
garyservin 0:fd24f7ca9688 95 for(unsigned int k= offset; k< offset+length_urdf_param_name; ++k){
garyservin 0:fd24f7ca9688 96 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 97 }
garyservin 0:fd24f7ca9688 98 inbuffer[offset+length_urdf_param_name-1]=0;
garyservin 0:fd24f7ca9688 99 this->urdf_param_name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 100 offset += length_urdf_param_name;
garyservin 0:fd24f7ca9688 101 uint8_t joint_names_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 102 if(joint_names_lengthT > joint_names_length)
garyservin 0:fd24f7ca9688 103 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
garyservin 0:fd24f7ca9688 104 offset += 3;
garyservin 0:fd24f7ca9688 105 joint_names_length = joint_names_lengthT;
garyservin 0:fd24f7ca9688 106 for( uint8_t i = 0; i < joint_names_length; i++){
garyservin 0:fd24f7ca9688 107 uint32_t length_st_joint_names;
garyservin 0:fd24f7ca9688 108 memcpy(&length_st_joint_names, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 109 offset += 4;
garyservin 0:fd24f7ca9688 110 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
garyservin 0:fd24f7ca9688 111 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 112 }
garyservin 0:fd24f7ca9688 113 inbuffer[offset+length_st_joint_names-1]=0;
garyservin 0:fd24f7ca9688 114 this->st_joint_names = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 115 offset += length_st_joint_names;
garyservin 0:fd24f7ca9688 116 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
garyservin 0:fd24f7ca9688 117 }
garyservin 0:fd24f7ca9688 118 uint8_t joint_positions_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 119 if(joint_positions_lengthT > joint_positions_length)
garyservin 0:fd24f7ca9688 120 this->joint_positions = (double*)realloc(this->joint_positions, joint_positions_lengthT * sizeof(double));
garyservin 0:fd24f7ca9688 121 offset += 3;
garyservin 0:fd24f7ca9688 122 joint_positions_length = joint_positions_lengthT;
garyservin 0:fd24f7ca9688 123 for( uint8_t i = 0; i < joint_positions_length; i++){
garyservin 0:fd24f7ca9688 124 union {
garyservin 0:fd24f7ca9688 125 double real;
garyservin 0:fd24f7ca9688 126 uint64_t base;
garyservin 0:fd24f7ca9688 127 } u_st_joint_positions;
garyservin 0:fd24f7ca9688 128 u_st_joint_positions.base = 0;
garyservin 0:fd24f7ca9688 129 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 130 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 131 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 132 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 133 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:fd24f7ca9688 134 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:fd24f7ca9688 135 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:fd24f7ca9688 136 u_st_joint_positions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:fd24f7ca9688 137 this->st_joint_positions = u_st_joint_positions.real;
garyservin 0:fd24f7ca9688 138 offset += sizeof(this->st_joint_positions);
garyservin 0:fd24f7ca9688 139 memcpy( &(this->joint_positions[i]), &(this->st_joint_positions), sizeof(double));
garyservin 0:fd24f7ca9688 140 }
garyservin 0:fd24f7ca9688 141 return offset;
garyservin 0:fd24f7ca9688 142 }
garyservin 0:fd24f7ca9688 143
garyservin 0:fd24f7ca9688 144 const char * getType(){ return SETMODELCONFIGURATION; };
garyservin 0:fd24f7ca9688 145 const char * getMD5(){ return "160eae60f51fabff255480c70afa289f"; };
garyservin 0:fd24f7ca9688 146
garyservin 0:fd24f7ca9688 147 };
garyservin 0:fd24f7ca9688 148
garyservin 0:fd24f7ca9688 149 class SetModelConfigurationResponse : public ros::Msg
garyservin 0:fd24f7ca9688 150 {
garyservin 0:fd24f7ca9688 151 public:
garyservin 0:fd24f7ca9688 152 bool success;
garyservin 0:fd24f7ca9688 153 const char* status_message;
garyservin 0:fd24f7ca9688 154
garyservin 0:fd24f7ca9688 155 SetModelConfigurationResponse():
garyservin 0:fd24f7ca9688 156 success(0),
garyservin 0:fd24f7ca9688 157 status_message("")
garyservin 0:fd24f7ca9688 158 {
garyservin 0:fd24f7ca9688 159 }
garyservin 0:fd24f7ca9688 160
garyservin 0:fd24f7ca9688 161 virtual int serialize(unsigned char *outbuffer) const
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.real = this->success;
garyservin 0:fd24f7ca9688 169 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 170 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 171 uint32_t length_status_message = strlen(this->status_message);
garyservin 0:fd24f7ca9688 172 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 173 offset += 4;
garyservin 0:fd24f7ca9688 174 memcpy(outbuffer + offset, this->status_message, length_status_message);
garyservin 0:fd24f7ca9688 175 offset += length_status_message;
garyservin 0:fd24f7ca9688 176 return offset;
garyservin 0:fd24f7ca9688 177 }
garyservin 0:fd24f7ca9688 178
garyservin 0:fd24f7ca9688 179 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 180 {
garyservin 0:fd24f7ca9688 181 int offset = 0;
garyservin 0:fd24f7ca9688 182 union {
garyservin 0:fd24f7ca9688 183 bool real;
garyservin 0:fd24f7ca9688 184 uint8_t base;
garyservin 0:fd24f7ca9688 185 } u_success;
garyservin 0:fd24f7ca9688 186 u_success.base = 0;
garyservin 0:fd24f7ca9688 187 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 188 this->success = u_success.real;
garyservin 0:fd24f7ca9688 189 offset += sizeof(this->success);
garyservin 0:fd24f7ca9688 190 uint32_t length_status_message;
garyservin 0:fd24f7ca9688 191 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 192 offset += 4;
garyservin 0:fd24f7ca9688 193 for(unsigned int k= offset; k< offset+length_status_message; ++k){
garyservin 0:fd24f7ca9688 194 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 195 }
garyservin 0:fd24f7ca9688 196 inbuffer[offset+length_status_message-1]=0;
garyservin 0:fd24f7ca9688 197 this->status_message = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 198 offset += length_status_message;
garyservin 0:fd24f7ca9688 199 return offset;
garyservin 0:fd24f7ca9688 200 }
garyservin 0:fd24f7ca9688 201
garyservin 0:fd24f7ca9688 202 const char * getType(){ return SETMODELCONFIGURATION; };
garyservin 0:fd24f7ca9688 203 const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
garyservin 0:fd24f7ca9688 204
garyservin 0:fd24f7ca9688 205 };
garyservin 0:fd24f7ca9688 206
garyservin 0:fd24f7ca9688 207 class SetModelConfiguration {
garyservin 0:fd24f7ca9688 208 public:
garyservin 0:fd24f7ca9688 209 typedef SetModelConfigurationRequest Request;
garyservin 0:fd24f7ca9688 210 typedef SetModelConfigurationResponse Response;
garyservin 0:fd24f7ca9688 211 };
garyservin 0:fd24f7ca9688 212
garyservin 0:fd24f7ca9688 213 }
garyservin 0:fd24f7ca9688 214 #endif