ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
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(); } }
sensor_msgs/NavSatStatus.h@0:fd24f7ca9688, 2016-03-31 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:fd24f7ca9688 | 1 | #ifndef _ROS_sensor_msgs_NavSatStatus_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_sensor_msgs_NavSatStatus_h |
garyservin | 0:fd24f7ca9688 | 3 | |
garyservin | 0:fd24f7ca9688 | 4 | #include <stdint.h> |
garyservin | 0:fd24f7ca9688 | 5 | #include <string.h> |
garyservin | 0:fd24f7ca9688 | 6 | #include <stdlib.h> |
garyservin | 0:fd24f7ca9688 | 7 | #include "ros/msg.h" |
garyservin | 0:fd24f7ca9688 | 8 | |
garyservin | 0:fd24f7ca9688 | 9 | namespace sensor_msgs |
garyservin | 0:fd24f7ca9688 | 10 | { |
garyservin | 0:fd24f7ca9688 | 11 | |
garyservin | 0:fd24f7ca9688 | 12 | class NavSatStatus : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 13 | { |
garyservin | 0:fd24f7ca9688 | 14 | public: |
garyservin | 0:fd24f7ca9688 | 15 | int8_t status; |
garyservin | 0:fd24f7ca9688 | 16 | uint16_t service; |
garyservin | 0:fd24f7ca9688 | 17 | enum { STATUS_NO_FIX = -1 }; |
garyservin | 0:fd24f7ca9688 | 18 | enum { STATUS_FIX = 0 }; |
garyservin | 0:fd24f7ca9688 | 19 | enum { STATUS_SBAS_FIX = 1 }; |
garyservin | 0:fd24f7ca9688 | 20 | enum { STATUS_GBAS_FIX = 2 }; |
garyservin | 0:fd24f7ca9688 | 21 | enum { SERVICE_GPS = 1 }; |
garyservin | 0:fd24f7ca9688 | 22 | enum { SERVICE_GLONASS = 2 }; |
garyservin | 0:fd24f7ca9688 | 23 | enum { SERVICE_COMPASS = 4 }; |
garyservin | 0:fd24f7ca9688 | 24 | enum { SERVICE_GALILEO = 8 }; |
garyservin | 0:fd24f7ca9688 | 25 | |
garyservin | 0:fd24f7ca9688 | 26 | NavSatStatus(): |
garyservin | 0:fd24f7ca9688 | 27 | status(0), |
garyservin | 0:fd24f7ca9688 | 28 | service(0) |
garyservin | 0:fd24f7ca9688 | 29 | { |
garyservin | 0:fd24f7ca9688 | 30 | } |
garyservin | 0:fd24f7ca9688 | 31 | |
garyservin | 0:fd24f7ca9688 | 32 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 33 | { |
garyservin | 0:fd24f7ca9688 | 34 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 35 | union { |
garyservin | 0:fd24f7ca9688 | 36 | int8_t real; |
garyservin | 0:fd24f7ca9688 | 37 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 38 | } u_status; |
garyservin | 0:fd24f7ca9688 | 39 | u_status.real = this->status; |
garyservin | 0:fd24f7ca9688 | 40 | *(outbuffer + offset + 0) = (u_status.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 41 | offset += sizeof(this->status); |
garyservin | 0:fd24f7ca9688 | 42 | *(outbuffer + offset + 0) = (this->service >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 43 | *(outbuffer + offset + 1) = (this->service >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 44 | offset += sizeof(this->service); |
garyservin | 0:fd24f7ca9688 | 45 | return offset; |
garyservin | 0:fd24f7ca9688 | 46 | } |
garyservin | 0:fd24f7ca9688 | 47 | |
garyservin | 0:fd24f7ca9688 | 48 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 49 | { |
garyservin | 0:fd24f7ca9688 | 50 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 51 | union { |
garyservin | 0:fd24f7ca9688 | 52 | int8_t real; |
garyservin | 0:fd24f7ca9688 | 53 | uint8_t base; |
garyservin | 0:fd24f7ca9688 | 54 | } u_status; |
garyservin | 0:fd24f7ca9688 | 55 | u_status.base = 0; |
garyservin | 0:fd24f7ca9688 | 56 | u_status.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 57 | this->status = u_status.real; |
garyservin | 0:fd24f7ca9688 | 58 | offset += sizeof(this->status); |
garyservin | 0:fd24f7ca9688 | 59 | this->service = ((uint16_t) (*(inbuffer + offset))); |
garyservin | 0:fd24f7ca9688 | 60 | this->service |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 61 | offset += sizeof(this->service); |
garyservin | 0:fd24f7ca9688 | 62 | return offset; |
garyservin | 0:fd24f7ca9688 | 63 | } |
garyservin | 0:fd24f7ca9688 | 64 | |
garyservin | 0:fd24f7ca9688 | 65 | const char * getType(){ return "sensor_msgs/NavSatStatus"; }; |
garyservin | 0:fd24f7ca9688 | 66 | const char * getMD5(){ return "331cdbddfa4bc96ffc3b9ad98900a54c"; }; |
garyservin | 0:fd24f7ca9688 | 67 | |
garyservin | 0:fd24f7ca9688 | 68 | }; |
garyservin | 0:fd24f7ca9688 | 69 | |
garyservin | 0:fd24f7ca9688 | 70 | } |
garyservin | 0:fd24f7ca9688 | 71 | #endif |