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(); } }
nav_msgs/GetMapAction.h
- Committer:
- garyservin
- Date:
- 2016-03-31
- Revision:
- 0:fd24f7ca9688
File content as of revision 0:fd24f7ca9688:
#ifndef _ROS_nav_msgs_GetMapAction_h #define _ROS_nav_msgs_GetMapAction_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "nav_msgs/GetMapActionGoal.h" #include "nav_msgs/GetMapActionResult.h" #include "nav_msgs/GetMapActionFeedback.h" namespace nav_msgs { class GetMapAction : public ros::Msg { public: nav_msgs::GetMapActionGoal action_goal; nav_msgs::GetMapActionResult action_result; nav_msgs::GetMapActionFeedback action_feedback; GetMapAction(): action_goal(), action_result(), action_feedback() { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->action_goal.serialize(outbuffer + offset); offset += this->action_result.serialize(outbuffer + offset); offset += this->action_feedback.serialize(outbuffer + offset); return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->action_goal.deserialize(inbuffer + offset); offset += this->action_result.deserialize(inbuffer + offset); offset += this->action_feedback.deserialize(inbuffer + offset); return offset; } const char * getType(){ return "nav_msgs/GetMapAction"; }; const char * getMD5(){ return "e611ad23fbf237c031b7536416dc7cd7"; }; }; } #endif