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();
    }
}

rosserial_msgs/RequestServiceInfo.h

Committer:
Gary Servin
Date:
2019-11-08
Revision:
0:04ac6be8229a

File content as of revision 0:04ac6be8229a:

#ifndef _ROS_SERVICE_RequestServiceInfo_h
#define _ROS_SERVICE_RequestServiceInfo_h
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include "ros/msg.h"

namespace rosserial_msgs
{

static const char REQUESTSERVICEINFO[] = "rosserial_msgs/RequestServiceInfo";

  class RequestServiceInfoRequest : public ros::Msg
  {
    public:
      typedef const char* _service_type;
      _service_type service;

    RequestServiceInfoRequest():
      service("")
    {
    }

    virtual int serialize(unsigned char *outbuffer) const
    {
      int offset = 0;
      uint32_t length_service = strlen(this->service);
      varToArr(outbuffer + offset, length_service);
      offset += 4;
      memcpy(outbuffer + offset, this->service, length_service);
      offset += length_service;
      return offset;
    }

    virtual int deserialize(unsigned char *inbuffer)
    {
      int offset = 0;
      uint32_t length_service;
      arrToVar(length_service, (inbuffer + offset));
      offset += 4;
      for(unsigned int k= offset; k< offset+length_service; ++k){
          inbuffer[k-1]=inbuffer[k];
      }
      inbuffer[offset+length_service-1]=0;
      this->service = (char *)(inbuffer + offset-1);
      offset += length_service;
     return offset;
    }

    const char * getType(){ return REQUESTSERVICEINFO; };
    const char * getMD5(){ return "1cbcfa13b08f6d36710b9af8741e6112"; };

  };

  class RequestServiceInfoResponse : public ros::Msg
  {
    public:
      typedef const char* _service_md5_type;
      _service_md5_type service_md5;
      typedef const char* _request_md5_type;
      _request_md5_type request_md5;
      typedef const char* _response_md5_type;
      _response_md5_type response_md5;

    RequestServiceInfoResponse():
      service_md5(""),
      request_md5(""),
      response_md5("")
    {
    }

    virtual int serialize(unsigned char *outbuffer) const
    {
      int offset = 0;
      uint32_t length_service_md5 = strlen(this->service_md5);
      varToArr(outbuffer + offset, length_service_md5);
      offset += 4;
      memcpy(outbuffer + offset, this->service_md5, length_service_md5);
      offset += length_service_md5;
      uint32_t length_request_md5 = strlen(this->request_md5);
      varToArr(outbuffer + offset, length_request_md5);
      offset += 4;
      memcpy(outbuffer + offset, this->request_md5, length_request_md5);
      offset += length_request_md5;
      uint32_t length_response_md5 = strlen(this->response_md5);
      varToArr(outbuffer + offset, length_response_md5);
      offset += 4;
      memcpy(outbuffer + offset, this->response_md5, length_response_md5);
      offset += length_response_md5;
      return offset;
    }

    virtual int deserialize(unsigned char *inbuffer)
    {
      int offset = 0;
      uint32_t length_service_md5;
      arrToVar(length_service_md5, (inbuffer + offset));
      offset += 4;
      for(unsigned int k= offset; k< offset+length_service_md5; ++k){
          inbuffer[k-1]=inbuffer[k];
      }
      inbuffer[offset+length_service_md5-1]=0;
      this->service_md5 = (char *)(inbuffer + offset-1);
      offset += length_service_md5;
      uint32_t length_request_md5;
      arrToVar(length_request_md5, (inbuffer + offset));
      offset += 4;
      for(unsigned int k= offset; k< offset+length_request_md5; ++k){
          inbuffer[k-1]=inbuffer[k];
      }
      inbuffer[offset+length_request_md5-1]=0;
      this->request_md5 = (char *)(inbuffer + offset-1);
      offset += length_request_md5;
      uint32_t length_response_md5;
      arrToVar(length_response_md5, (inbuffer + offset));
      offset += 4;
      for(unsigned int k= offset; k< offset+length_response_md5; ++k){
          inbuffer[k-1]=inbuffer[k];
      }
      inbuffer[offset+length_response_md5-1]=0;
      this->response_md5 = (char *)(inbuffer + offset-1);
      offset += length_response_md5;
     return offset;
    }

    const char * getType(){ return REQUESTSERVICEINFO; };
    const char * getMD5(){ return "c3d6dd25b909596479fbbc6559fa6874"; };

  };

  class RequestServiceInfo {
    public:
    typedef RequestServiceInfoRequest Request;
    typedef RequestServiceInfoResponse Response;
  };

}
#endif