ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more
ROSSerial_mbed for Kinetic 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_kinetic
rosserial_mbed Hello World example for Kinetic Kame distribution
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(); } }
Revision 1:a849bf78d77f, committed 2016-12-31
- Comitter:
- garyservin
- Date:
- Sat Dec 31 00:59:58 2016 +0000
- Parent:
- 0:9e9b7db60fd5
- Commit message:
- Add missing round() method
Changed in this revision
ros/duration.h | Show annotated file Show diff for this revision Revisions of this file |
ros/time.h | Show annotated file Show diff for this revision Revisions of this file |
diff -r 9e9b7db60fd5 -r a849bf78d77f ros/duration.h --- a/ros/duration.h Sat Dec 31 00:48:34 2016 +0000 +++ b/ros/duration.h Sat Dec 31 00:59:58 2016 +0000 @@ -53,6 +53,7 @@ normalizeSecNSecSigned(sec, nsec); } + double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); } double toSec() const { return (double)sec + 1e-9*(double)nsec; }; void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); };
diff -r 9e9b7db60fd5 -r a849bf78d77f ros/time.h --- a/ros/time.h Sat Dec 31 00:48:34 2016 +0000 +++ b/ros/time.h Sat Dec 31 00:59:58 2016 +0000 @@ -54,6 +54,7 @@ normalizeSecNSec(sec, nsec); } + double round(double number) { return number < 0.0 ? ceil(number - 0.5): floor(number + 0.5); } double toSec() const { return (double)sec + 1e-9*(double)nsec; }; void fromSec(double t) { sec = (uint32_t) floor(t); nsec = (uint32_t) round((t-sec) * 1e9); };