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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more

ROSSerial_mbed for Melodic 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_melodic

rosserial_mbed Hello World example for Melodic Morenia distribution

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:
Gary Servin
Date:
Fri Nov 08 14:55:04 2019 -0300
Revision:
1:da82487f547e
Parent:
0:04ac6be8229a
Add missing round() method

Who changed what in which revision?

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