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(); } }
std_msgs/Int32MultiArray.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_std_msgs_Int32MultiArray_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_std_msgs_Int32MultiArray_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 | #include "std_msgs/MultiArrayLayout.h" |
garyservin | 0:fd24f7ca9688 | 9 | |
garyservin | 0:fd24f7ca9688 | 10 | namespace std_msgs |
garyservin | 0:fd24f7ca9688 | 11 | { |
garyservin | 0:fd24f7ca9688 | 12 | |
garyservin | 0:fd24f7ca9688 | 13 | class Int32MultiArray : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 14 | { |
garyservin | 0:fd24f7ca9688 | 15 | public: |
garyservin | 0:fd24f7ca9688 | 16 | std_msgs::MultiArrayLayout layout; |
garyservin | 0:fd24f7ca9688 | 17 | uint8_t data_length; |
garyservin | 0:fd24f7ca9688 | 18 | int32_t st_data; |
garyservin | 0:fd24f7ca9688 | 19 | int32_t * data; |
garyservin | 0:fd24f7ca9688 | 20 | |
garyservin | 0:fd24f7ca9688 | 21 | Int32MultiArray(): |
garyservin | 0:fd24f7ca9688 | 22 | layout(), |
garyservin | 0:fd24f7ca9688 | 23 | data_length(0), data(NULL) |
garyservin | 0:fd24f7ca9688 | 24 | { |
garyservin | 0:fd24f7ca9688 | 25 | } |
garyservin | 0:fd24f7ca9688 | 26 | |
garyservin | 0:fd24f7ca9688 | 27 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 28 | { |
garyservin | 0:fd24f7ca9688 | 29 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 30 | offset += this->layout.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 31 | *(outbuffer + offset++) = data_length; |
garyservin | 0:fd24f7ca9688 | 32 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 33 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 34 | *(outbuffer + offset++) = 0; |
garyservin | 0:fd24f7ca9688 | 35 | for( uint8_t i = 0; i < data_length; i++){ |
garyservin | 0:fd24f7ca9688 | 36 | union { |
garyservin | 0:fd24f7ca9688 | 37 | int32_t real; |
garyservin | 0:fd24f7ca9688 | 38 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 39 | } u_datai; |
garyservin | 0:fd24f7ca9688 | 40 | u_datai.real = this->data[i]; |
garyservin | 0:fd24f7ca9688 | 41 | *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 42 | *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 43 | *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 44 | *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 45 | offset += sizeof(this->data[i]); |
garyservin | 0:fd24f7ca9688 | 46 | } |
garyservin | 0:fd24f7ca9688 | 47 | return offset; |
garyservin | 0:fd24f7ca9688 | 48 | } |
garyservin | 0:fd24f7ca9688 | 49 | |
garyservin | 0:fd24f7ca9688 | 50 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 51 | { |
garyservin | 0:fd24f7ca9688 | 52 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 53 | offset += this->layout.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 54 | uint8_t data_lengthT = *(inbuffer + offset++); |
garyservin | 0:fd24f7ca9688 | 55 | if(data_lengthT > data_length) |
garyservin | 0:fd24f7ca9688 | 56 | this->data = (int32_t*)realloc(this->data, data_lengthT * sizeof(int32_t)); |
garyservin | 0:fd24f7ca9688 | 57 | offset += 3; |
garyservin | 0:fd24f7ca9688 | 58 | data_length = data_lengthT; |
garyservin | 0:fd24f7ca9688 | 59 | for( uint8_t i = 0; i < data_length; i++){ |
garyservin | 0:fd24f7ca9688 | 60 | union { |
garyservin | 0:fd24f7ca9688 | 61 | int32_t real; |
garyservin | 0:fd24f7ca9688 | 62 | uint32_t base; |
garyservin | 0:fd24f7ca9688 | 63 | } u_st_data; |
garyservin | 0:fd24f7ca9688 | 64 | u_st_data.base = 0; |
garyservin | 0:fd24f7ca9688 | 65 | u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 66 | u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 67 | u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 68 | u_st_data.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 69 | this->st_data = u_st_data.real; |
garyservin | 0:fd24f7ca9688 | 70 | offset += sizeof(this->st_data); |
garyservin | 0:fd24f7ca9688 | 71 | memcpy( &(this->data[i]), &(this->st_data), sizeof(int32_t)); |
garyservin | 0:fd24f7ca9688 | 72 | } |
garyservin | 0:fd24f7ca9688 | 73 | return offset; |
garyservin | 0:fd24f7ca9688 | 74 | } |
garyservin | 0:fd24f7ca9688 | 75 | |
garyservin | 0:fd24f7ca9688 | 76 | const char * getType(){ return "std_msgs/Int32MultiArray"; }; |
garyservin | 0:fd24f7ca9688 | 77 | const char * getMD5(){ return "1d99f79f8b325b44fee908053e9c945b"; }; |
garyservin | 0:fd24f7ca9688 | 78 | |
garyservin | 0:fd24f7ca9688 | 79 | }; |
garyservin | 0:fd24f7ca9688 | 80 | |
garyservin | 0:fd24f7ca9688 | 81 | } |
garyservin | 0:fd24f7ca9688 | 82 | #endif |