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(); } }
turtlesim/Spawn.h
- Committer:
- garyservin
- Date:
- 2016-03-31
- Revision:
- 0:fd24f7ca9688
File content as of revision 0:fd24f7ca9688:
#ifndef _ROS_SERVICE_Spawn_h #define _ROS_SERVICE_Spawn_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" namespace turtlesim { static const char SPAWN[] = "turtlesim/Spawn"; class SpawnRequest : public ros::Msg { public: float x; float y; float theta; const char* name; SpawnRequest(): x(0), y(0), theta(0), name("") { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; union { float real; uint32_t base; } u_x; u_x.real = this->x; *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; offset += sizeof(this->x); union { float real; uint32_t base; } u_y; u_y.real = this->y; *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; offset += sizeof(this->y); union { float real; uint32_t base; } u_theta; u_theta.real = this->theta; *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF; offset += sizeof(this->theta); uint32_t length_name = strlen(this->name); memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); offset += 4; memcpy(outbuffer + offset, this->name, length_name); offset += length_name; return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; union { float real; uint32_t base; } u_x; u_x.base = 0; u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); this->x = u_x.real; offset += sizeof(this->x); union { float real; uint32_t base; } u_y; u_y.base = 0; u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); this->y = u_y.real; offset += sizeof(this->y); union { float real; uint32_t base; } u_theta; u_theta.base = 0; u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); this->theta = u_theta.real; offset += sizeof(this->theta); uint32_t length_name; memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); offset += 4; for(unsigned int k= offset; k< offset+length_name; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_name-1]=0; this->name = (char *)(inbuffer + offset-1); offset += length_name; return offset; } const char * getType(){ return SPAWN; }; const char * getMD5(){ return "57f001c49ab7b11d699f8606c1f4f7ff"; }; }; class SpawnResponse : public ros::Msg { public: const char* name; SpawnResponse(): name("") { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; uint32_t length_name = strlen(this->name); memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); offset += 4; memcpy(outbuffer + offset, this->name, length_name); offset += length_name; return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; uint32_t length_name; memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); offset += 4; for(unsigned int k= offset; k< offset+length_name; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_name-1]=0; this->name = (char *)(inbuffer + offset-1); offset += length_name; return offset; } const char * getType(){ return SPAWN; }; const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; }; class Spawn { public: typedef SpawnRequest Request; typedef SpawnResponse Response; }; } #endif