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/Joy.h
- Committer:
- garyservin
- Date:
- 2016-03-31
- Revision:
- 0:fd24f7ca9688
File content as of revision 0:fd24f7ca9688:
#ifndef _ROS_sensor_msgs_Joy_h #define _ROS_sensor_msgs_Joy_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "std_msgs/Header.h" namespace sensor_msgs { class Joy : public ros::Msg { public: std_msgs::Header header; uint8_t axes_length; float st_axes; float * axes; uint8_t buttons_length; int32_t st_buttons; int32_t * buttons; Joy(): header(), axes_length(0), axes(NULL), buttons_length(0), buttons(NULL) { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); *(outbuffer + offset++) = axes_length; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; for( uint8_t i = 0; i < axes_length; i++){ union { float real; uint32_t base; } u_axesi; u_axesi.real = this->axes[i]; *(outbuffer + offset + 0) = (u_axesi.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_axesi.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_axesi.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_axesi.base >> (8 * 3)) & 0xFF; offset += sizeof(this->axes[i]); } *(outbuffer + offset++) = buttons_length; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; for( uint8_t i = 0; i < buttons_length; i++){ union { int32_t real; uint32_t base; } u_buttonsi; u_buttonsi.real = this->buttons[i]; *(outbuffer + offset + 0) = (u_buttonsi.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_buttonsi.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_buttonsi.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_buttonsi.base >> (8 * 3)) & 0xFF; offset += sizeof(this->buttons[i]); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->header.deserialize(inbuffer + offset); uint8_t axes_lengthT = *(inbuffer + offset++); if(axes_lengthT > axes_length) this->axes = (float*)realloc(this->axes, axes_lengthT * sizeof(float)); offset += 3; axes_length = axes_lengthT; for( uint8_t i = 0; i < axes_length; i++){ union { float real; uint32_t base; } u_st_axes; u_st_axes.base = 0; u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); u_st_axes.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); this->st_axes = u_st_axes.real; offset += sizeof(this->st_axes); memcpy( &(this->axes[i]), &(this->st_axes), sizeof(float)); } uint8_t buttons_lengthT = *(inbuffer + offset++); if(buttons_lengthT > buttons_length) this->buttons = (int32_t*)realloc(this->buttons, buttons_lengthT * sizeof(int32_t)); offset += 3; buttons_length = buttons_lengthT; for( uint8_t i = 0; i < buttons_length; i++){ union { int32_t real; uint32_t base; } u_st_buttons; u_st_buttons.base = 0; u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); u_st_buttons.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); this->st_buttons = u_st_buttons.real; offset += sizeof(this->st_buttons); memcpy( &(this->buttons[i]), &(this->st_buttons), sizeof(int32_t)); } return offset; } const char * getType(){ return "sensor_msgs/Joy"; }; const char * getMD5(){ return "5a9ea5f83505693b71e785041e67a8bb"; }; }; } #endif