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

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more

ROSSerial_mbed for Kinetic 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_kinetic

rosserial_mbed Hello World example for Kinetic Kame 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:
garyservin
Date:
Sat Dec 31 00:59:58 2016 +0000
Revision:
1:a849bf78d77f
Parent:
0:9e9b7db60fd5
Add missing round() method

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 9 #include "trajectory_msgs/MultiDOFJointTrajectoryPoint.h"
garyservin 0:9e9b7db60fd5 10
garyservin 0:9e9b7db60fd5 11 namespace trajectory_msgs
garyservin 0:9e9b7db60fd5 12 {
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class MultiDOFJointTrajectory : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 18 _header_type header;
garyservin 0:9e9b7db60fd5 19 uint32_t joint_names_length;
garyservin 0:9e9b7db60fd5 20 typedef char* _joint_names_type;
garyservin 0:9e9b7db60fd5 21 _joint_names_type st_joint_names;
garyservin 0:9e9b7db60fd5 22 _joint_names_type * joint_names;
garyservin 0:9e9b7db60fd5 23 uint32_t points_length;
garyservin 0:9e9b7db60fd5 24 typedef trajectory_msgs::MultiDOFJointTrajectoryPoint _points_type;
garyservin 0:9e9b7db60fd5 25 _points_type st_points;
garyservin 0:9e9b7db60fd5 26 _points_type * points;
garyservin 0:9e9b7db60fd5 27
garyservin 0:9e9b7db60fd5 28 MultiDOFJointTrajectory():
garyservin 0:9e9b7db60fd5 29 header(),
garyservin 0:9e9b7db60fd5 30 joint_names_length(0), joint_names(NULL),
garyservin 0:9e9b7db60fd5 31 points_length(0), points(NULL)
garyservin 0:9e9b7db60fd5 32 {
garyservin 0:9e9b7db60fd5 33 }
garyservin 0:9e9b7db60fd5 34
garyservin 0:9e9b7db60fd5 35 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 36 {
garyservin 0:9e9b7db60fd5 37 int offset = 0;
garyservin 0:9e9b7db60fd5 38 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 39 *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 40 *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 41 *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 42 *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 43 offset += sizeof(this->joint_names_length);
garyservin 0:9e9b7db60fd5 44 for( uint32_t i = 0; i < joint_names_length; i++){
garyservin 0:9e9b7db60fd5 45 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
garyservin 0:9e9b7db60fd5 46 varToArr(outbuffer + offset, length_joint_namesi);
garyservin 0:9e9b7db60fd5 47 offset += 4;
garyservin 0:9e9b7db60fd5 48 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
garyservin 0:9e9b7db60fd5 49 offset += length_joint_namesi;
garyservin 0:9e9b7db60fd5 50 }
garyservin 0:9e9b7db60fd5 51 *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 52 *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 53 *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 54 *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 55 offset += sizeof(this->points_length);
garyservin 0:9e9b7db60fd5 56 for( uint32_t i = 0; i < points_length; i++){
garyservin 0:9e9b7db60fd5 57 offset += this->points[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 58 }
garyservin 0:9e9b7db60fd5 59 return offset;
garyservin 0:9e9b7db60fd5 60 }
garyservin 0:9e9b7db60fd5 61
garyservin 0:9e9b7db60fd5 62 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 63 {
garyservin 0:9e9b7db60fd5 64 int offset = 0;
garyservin 0:9e9b7db60fd5 65 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 66 uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 67 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 68 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 69 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 70 offset += sizeof(this->joint_names_length);
garyservin 0:9e9b7db60fd5 71 if(joint_names_lengthT > joint_names_length)
garyservin 0:9e9b7db60fd5 72 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
garyservin 0:9e9b7db60fd5 73 joint_names_length = joint_names_lengthT;
garyservin 0:9e9b7db60fd5 74 for( uint32_t i = 0; i < joint_names_length; i++){
garyservin 0:9e9b7db60fd5 75 uint32_t length_st_joint_names;
garyservin 0:9e9b7db60fd5 76 arrToVar(length_st_joint_names, (inbuffer + offset));
garyservin 0:9e9b7db60fd5 77 offset += 4;
garyservin 0:9e9b7db60fd5 78 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
garyservin 0:9e9b7db60fd5 79 inbuffer[k-1]=inbuffer[k];
garyservin 0:9e9b7db60fd5 80 }
garyservin 0:9e9b7db60fd5 81 inbuffer[offset+length_st_joint_names-1]=0;
garyservin 0:9e9b7db60fd5 82 this->st_joint_names = (char *)(inbuffer + offset-1);
garyservin 0:9e9b7db60fd5 83 offset += length_st_joint_names;
garyservin 0:9e9b7db60fd5 84 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
garyservin 0:9e9b7db60fd5 85 }
garyservin 0:9e9b7db60fd5 86 uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 87 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 88 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 89 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 90 offset += sizeof(this->points_length);
garyservin 0:9e9b7db60fd5 91 if(points_lengthT > points_length)
garyservin 0:9e9b7db60fd5 92 this->points = (trajectory_msgs::MultiDOFJointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
garyservin 0:9e9b7db60fd5 93 points_length = points_lengthT;
garyservin 0:9e9b7db60fd5 94 for( uint32_t i = 0; i < points_length; i++){
garyservin 0:9e9b7db60fd5 95 offset += this->st_points.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 96 memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
garyservin 0:9e9b7db60fd5 97 }
garyservin 0:9e9b7db60fd5 98 return offset;
garyservin 0:9e9b7db60fd5 99 }
garyservin 0:9e9b7db60fd5 100
garyservin 0:9e9b7db60fd5 101 const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectory"; };
garyservin 0:9e9b7db60fd5 102 const char * getMD5(){ return "ef145a45a5f47b77b7f5cdde4b16c942"; };
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 };
garyservin 0:9e9b7db60fd5 105
garyservin 0:9e9b7db60fd5 106 }
garyservin 0:9e9b7db60fd5 107 #endif