ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_jade
ROSSerial_mbed for Jade 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_jade
rosserial_mbed Hello World example for jade 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(); } }
actionlib_msgs/GoalStatus.h@0:a906bb7c7831, 2016-03-31 (annotated)
- Committer:
- garyservin
- Date:
- Thu Mar 31 23:23:15 2016 +0000
- Revision:
- 0:a906bb7c7831
ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:a906bb7c7831 | 1 | #ifndef _ROS_actionlib_msgs_GoalStatus_h |
garyservin | 0:a906bb7c7831 | 2 | #define _ROS_actionlib_msgs_GoalStatus_h |
garyservin | 0:a906bb7c7831 | 3 | |
garyservin | 0:a906bb7c7831 | 4 | #include <stdint.h> |
garyservin | 0:a906bb7c7831 | 5 | #include <string.h> |
garyservin | 0:a906bb7c7831 | 6 | #include <stdlib.h> |
garyservin | 0:a906bb7c7831 | 7 | #include "ros/msg.h" |
garyservin | 0:a906bb7c7831 | 8 | #include "actionlib_msgs/GoalID.h" |
garyservin | 0:a906bb7c7831 | 9 | |
garyservin | 0:a906bb7c7831 | 10 | namespace actionlib_msgs |
garyservin | 0:a906bb7c7831 | 11 | { |
garyservin | 0:a906bb7c7831 | 12 | |
garyservin | 0:a906bb7c7831 | 13 | class GoalStatus : public ros::Msg |
garyservin | 0:a906bb7c7831 | 14 | { |
garyservin | 0:a906bb7c7831 | 15 | public: |
garyservin | 0:a906bb7c7831 | 16 | actionlib_msgs::GoalID goal_id; |
garyservin | 0:a906bb7c7831 | 17 | uint8_t status; |
garyservin | 0:a906bb7c7831 | 18 | const char* text; |
garyservin | 0:a906bb7c7831 | 19 | enum { PENDING = 0 }; |
garyservin | 0:a906bb7c7831 | 20 | enum { ACTIVE = 1 }; |
garyservin | 0:a906bb7c7831 | 21 | enum { PREEMPTED = 2 }; |
garyservin | 0:a906bb7c7831 | 22 | enum { SUCCEEDED = 3 }; |
garyservin | 0:a906bb7c7831 | 23 | enum { ABORTED = 4 }; |
garyservin | 0:a906bb7c7831 | 24 | enum { REJECTED = 5 }; |
garyservin | 0:a906bb7c7831 | 25 | enum { PREEMPTING = 6 }; |
garyservin | 0:a906bb7c7831 | 26 | enum { RECALLING = 7 }; |
garyservin | 0:a906bb7c7831 | 27 | enum { RECALLED = 8 }; |
garyservin | 0:a906bb7c7831 | 28 | enum { LOST = 9 }; |
garyservin | 0:a906bb7c7831 | 29 | |
garyservin | 0:a906bb7c7831 | 30 | GoalStatus(): |
garyservin | 0:a906bb7c7831 | 31 | goal_id(), |
garyservin | 0:a906bb7c7831 | 32 | status(0), |
garyservin | 0:a906bb7c7831 | 33 | text("") |
garyservin | 0:a906bb7c7831 | 34 | { |
garyservin | 0:a906bb7c7831 | 35 | } |
garyservin | 0:a906bb7c7831 | 36 | |
garyservin | 0:a906bb7c7831 | 37 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:a906bb7c7831 | 38 | { |
garyservin | 0:a906bb7c7831 | 39 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 40 | offset += this->goal_id.serialize(outbuffer + offset); |
garyservin | 0:a906bb7c7831 | 41 | *(outbuffer + offset + 0) = (this->status >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 42 | offset += sizeof(this->status); |
garyservin | 0:a906bb7c7831 | 43 | uint32_t length_text = strlen(this->text); |
garyservin | 0:a906bb7c7831 | 44 | memcpy(outbuffer + offset, &length_text, sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 45 | offset += 4; |
garyservin | 0:a906bb7c7831 | 46 | memcpy(outbuffer + offset, this->text, length_text); |
garyservin | 0:a906bb7c7831 | 47 | offset += length_text; |
garyservin | 0:a906bb7c7831 | 48 | return offset; |
garyservin | 0:a906bb7c7831 | 49 | } |
garyservin | 0:a906bb7c7831 | 50 | |
garyservin | 0:a906bb7c7831 | 51 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:a906bb7c7831 | 52 | { |
garyservin | 0:a906bb7c7831 | 53 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 54 | offset += this->goal_id.deserialize(inbuffer + offset); |
garyservin | 0:a906bb7c7831 | 55 | this->status = ((uint8_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 56 | offset += sizeof(this->status); |
garyservin | 0:a906bb7c7831 | 57 | uint32_t length_text; |
garyservin | 0:a906bb7c7831 | 58 | memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 59 | offset += 4; |
garyservin | 0:a906bb7c7831 | 60 | for(unsigned int k= offset; k< offset+length_text; ++k){ |
garyservin | 0:a906bb7c7831 | 61 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:a906bb7c7831 | 62 | } |
garyservin | 0:a906bb7c7831 | 63 | inbuffer[offset+length_text-1]=0; |
garyservin | 0:a906bb7c7831 | 64 | this->text = (char *)(inbuffer + offset-1); |
garyservin | 0:a906bb7c7831 | 65 | offset += length_text; |
garyservin | 0:a906bb7c7831 | 66 | return offset; |
garyservin | 0:a906bb7c7831 | 67 | } |
garyservin | 0:a906bb7c7831 | 68 | |
garyservin | 0:a906bb7c7831 | 69 | const char * getType(){ return "actionlib_msgs/GoalStatus"; }; |
garyservin | 0:a906bb7c7831 | 70 | const char * getMD5(){ return "d388f9b87b3c471f784434d671988d4a"; }; |
garyservin | 0:a906bb7c7831 | 71 | |
garyservin | 0:a906bb7c7831 | 72 | }; |
garyservin | 0:a906bb7c7831 | 73 | |
garyservin | 0:a906bb7c7831 | 74 | } |
garyservin | 0:a906bb7c7831 | 75 | #endif |