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(); } }
polled_camera/GetPolledImage.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_SERVICE_GetPolledImage_h |
garyservin | 0:a906bb7c7831 | 2 | #define _ROS_SERVICE_GetPolledImage_h |
garyservin | 0:a906bb7c7831 | 3 | #include <stdint.h> |
garyservin | 0:a906bb7c7831 | 4 | #include <string.h> |
garyservin | 0:a906bb7c7831 | 5 | #include <stdlib.h> |
garyservin | 0:a906bb7c7831 | 6 | #include "ros/msg.h" |
garyservin | 0:a906bb7c7831 | 7 | #include "sensor_msgs/RegionOfInterest.h" |
garyservin | 0:a906bb7c7831 | 8 | #include "ros/duration.h" |
garyservin | 0:a906bb7c7831 | 9 | #include "ros/time.h" |
garyservin | 0:a906bb7c7831 | 10 | |
garyservin | 0:a906bb7c7831 | 11 | namespace polled_camera |
garyservin | 0:a906bb7c7831 | 12 | { |
garyservin | 0:a906bb7c7831 | 13 | |
garyservin | 0:a906bb7c7831 | 14 | static const char GETPOLLEDIMAGE[] = "polled_camera/GetPolledImage"; |
garyservin | 0:a906bb7c7831 | 15 | |
garyservin | 0:a906bb7c7831 | 16 | class GetPolledImageRequest : public ros::Msg |
garyservin | 0:a906bb7c7831 | 17 | { |
garyservin | 0:a906bb7c7831 | 18 | public: |
garyservin | 0:a906bb7c7831 | 19 | const char* response_namespace; |
garyservin | 0:a906bb7c7831 | 20 | ros::Duration timeout; |
garyservin | 0:a906bb7c7831 | 21 | uint32_t binning_x; |
garyservin | 0:a906bb7c7831 | 22 | uint32_t binning_y; |
garyservin | 0:a906bb7c7831 | 23 | sensor_msgs::RegionOfInterest roi; |
garyservin | 0:a906bb7c7831 | 24 | |
garyservin | 0:a906bb7c7831 | 25 | GetPolledImageRequest(): |
garyservin | 0:a906bb7c7831 | 26 | response_namespace(""), |
garyservin | 0:a906bb7c7831 | 27 | timeout(), |
garyservin | 0:a906bb7c7831 | 28 | binning_x(0), |
garyservin | 0:a906bb7c7831 | 29 | binning_y(0), |
garyservin | 0:a906bb7c7831 | 30 | roi() |
garyservin | 0:a906bb7c7831 | 31 | { |
garyservin | 0:a906bb7c7831 | 32 | } |
garyservin | 0:a906bb7c7831 | 33 | |
garyservin | 0:a906bb7c7831 | 34 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:a906bb7c7831 | 35 | { |
garyservin | 0:a906bb7c7831 | 36 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 37 | uint32_t length_response_namespace = strlen(this->response_namespace); |
garyservin | 0:a906bb7c7831 | 38 | memcpy(outbuffer + offset, &length_response_namespace, sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 39 | offset += 4; |
garyservin | 0:a906bb7c7831 | 40 | memcpy(outbuffer + offset, this->response_namespace, length_response_namespace); |
garyservin | 0:a906bb7c7831 | 41 | offset += length_response_namespace; |
garyservin | 0:a906bb7c7831 | 42 | *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 43 | *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 44 | *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 45 | *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 46 | offset += sizeof(this->timeout.sec); |
garyservin | 0:a906bb7c7831 | 47 | *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 48 | *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 49 | *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 50 | *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 51 | offset += sizeof(this->timeout.nsec); |
garyservin | 0:a906bb7c7831 | 52 | *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 53 | *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 54 | *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 55 | *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 56 | offset += sizeof(this->binning_x); |
garyservin | 0:a906bb7c7831 | 57 | *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 58 | *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 59 | *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 60 | *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 61 | offset += sizeof(this->binning_y); |
garyservin | 0:a906bb7c7831 | 62 | offset += this->roi.serialize(outbuffer + offset); |
garyservin | 0:a906bb7c7831 | 63 | return offset; |
garyservin | 0:a906bb7c7831 | 64 | } |
garyservin | 0:a906bb7c7831 | 65 | |
garyservin | 0:a906bb7c7831 | 66 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:a906bb7c7831 | 67 | { |
garyservin | 0:a906bb7c7831 | 68 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 69 | uint32_t length_response_namespace; |
garyservin | 0:a906bb7c7831 | 70 | memcpy(&length_response_namespace, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 71 | offset += 4; |
garyservin | 0:a906bb7c7831 | 72 | for(unsigned int k= offset; k< offset+length_response_namespace; ++k){ |
garyservin | 0:a906bb7c7831 | 73 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:a906bb7c7831 | 74 | } |
garyservin | 0:a906bb7c7831 | 75 | inbuffer[offset+length_response_namespace-1]=0; |
garyservin | 0:a906bb7c7831 | 76 | this->response_namespace = (char *)(inbuffer + offset-1); |
garyservin | 0:a906bb7c7831 | 77 | offset += length_response_namespace; |
garyservin | 0:a906bb7c7831 | 78 | this->timeout.sec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 79 | this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 80 | this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 81 | this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 82 | offset += sizeof(this->timeout.sec); |
garyservin | 0:a906bb7c7831 | 83 | this->timeout.nsec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 84 | this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 85 | this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 86 | this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 87 | offset += sizeof(this->timeout.nsec); |
garyservin | 0:a906bb7c7831 | 88 | this->binning_x = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 89 | this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 90 | this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 91 | this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 92 | offset += sizeof(this->binning_x); |
garyservin | 0:a906bb7c7831 | 93 | this->binning_y = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 94 | this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 95 | this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 96 | this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 97 | offset += sizeof(this->binning_y); |
garyservin | 0:a906bb7c7831 | 98 | offset += this->roi.deserialize(inbuffer + offset); |
garyservin | 0:a906bb7c7831 | 99 | return offset; |
garyservin | 0:a906bb7c7831 | 100 | } |
garyservin | 0:a906bb7c7831 | 101 | |
garyservin | 0:a906bb7c7831 | 102 | const char * getType(){ return GETPOLLEDIMAGE; }; |
garyservin | 0:a906bb7c7831 | 103 | const char * getMD5(){ return "c77ed43e530fd48e9e7a2a93845e154c"; }; |
garyservin | 0:a906bb7c7831 | 104 | |
garyservin | 0:a906bb7c7831 | 105 | }; |
garyservin | 0:a906bb7c7831 | 106 | |
garyservin | 0:a906bb7c7831 | 107 | class GetPolledImageResponse : public ros::Msg |
garyservin | 0:a906bb7c7831 | 108 | { |
garyservin | 0:a906bb7c7831 | 109 | public: |
garyservin | 0:a906bb7c7831 | 110 | bool success; |
garyservin | 0:a906bb7c7831 | 111 | const char* status_message; |
garyservin | 0:a906bb7c7831 | 112 | ros::Time stamp; |
garyservin | 0:a906bb7c7831 | 113 | |
garyservin | 0:a906bb7c7831 | 114 | GetPolledImageResponse(): |
garyservin | 0:a906bb7c7831 | 115 | success(0), |
garyservin | 0:a906bb7c7831 | 116 | status_message(""), |
garyservin | 0:a906bb7c7831 | 117 | stamp() |
garyservin | 0:a906bb7c7831 | 118 | { |
garyservin | 0:a906bb7c7831 | 119 | } |
garyservin | 0:a906bb7c7831 | 120 | |
garyservin | 0:a906bb7c7831 | 121 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:a906bb7c7831 | 122 | { |
garyservin | 0:a906bb7c7831 | 123 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 124 | union { |
garyservin | 0:a906bb7c7831 | 125 | bool real; |
garyservin | 0:a906bb7c7831 | 126 | uint8_t base; |
garyservin | 0:a906bb7c7831 | 127 | } u_success; |
garyservin | 0:a906bb7c7831 | 128 | u_success.real = this->success; |
garyservin | 0:a906bb7c7831 | 129 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 130 | offset += sizeof(this->success); |
garyservin | 0:a906bb7c7831 | 131 | uint32_t length_status_message = strlen(this->status_message); |
garyservin | 0:a906bb7c7831 | 132 | memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 133 | offset += 4; |
garyservin | 0:a906bb7c7831 | 134 | memcpy(outbuffer + offset, this->status_message, length_status_message); |
garyservin | 0:a906bb7c7831 | 135 | offset += length_status_message; |
garyservin | 0:a906bb7c7831 | 136 | *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 137 | *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 138 | *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 139 | *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 140 | offset += sizeof(this->stamp.sec); |
garyservin | 0:a906bb7c7831 | 141 | *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 142 | *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 143 | *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 144 | *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 145 | offset += sizeof(this->stamp.nsec); |
garyservin | 0:a906bb7c7831 | 146 | return offset; |
garyservin | 0:a906bb7c7831 | 147 | } |
garyservin | 0:a906bb7c7831 | 148 | |
garyservin | 0:a906bb7c7831 | 149 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:a906bb7c7831 | 150 | { |
garyservin | 0:a906bb7c7831 | 151 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 152 | union { |
garyservin | 0:a906bb7c7831 | 153 | bool real; |
garyservin | 0:a906bb7c7831 | 154 | uint8_t base; |
garyservin | 0:a906bb7c7831 | 155 | } u_success; |
garyservin | 0:a906bb7c7831 | 156 | u_success.base = 0; |
garyservin | 0:a906bb7c7831 | 157 | u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:a906bb7c7831 | 158 | this->success = u_success.real; |
garyservin | 0:a906bb7c7831 | 159 | offset += sizeof(this->success); |
garyservin | 0:a906bb7c7831 | 160 | uint32_t length_status_message; |
garyservin | 0:a906bb7c7831 | 161 | memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 162 | offset += 4; |
garyservin | 0:a906bb7c7831 | 163 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
garyservin | 0:a906bb7c7831 | 164 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:a906bb7c7831 | 165 | } |
garyservin | 0:a906bb7c7831 | 166 | inbuffer[offset+length_status_message-1]=0; |
garyservin | 0:a906bb7c7831 | 167 | this->status_message = (char *)(inbuffer + offset-1); |
garyservin | 0:a906bb7c7831 | 168 | offset += length_status_message; |
garyservin | 0:a906bb7c7831 | 169 | this->stamp.sec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 170 | this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 171 | this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 172 | this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 173 | offset += sizeof(this->stamp.sec); |
garyservin | 0:a906bb7c7831 | 174 | this->stamp.nsec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 175 | this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 176 | this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 177 | this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 178 | offset += sizeof(this->stamp.nsec); |
garyservin | 0:a906bb7c7831 | 179 | return offset; |
garyservin | 0:a906bb7c7831 | 180 | } |
garyservin | 0:a906bb7c7831 | 181 | |
garyservin | 0:a906bb7c7831 | 182 | const char * getType(){ return GETPOLLEDIMAGE; }; |
garyservin | 0:a906bb7c7831 | 183 | const char * getMD5(){ return "dbf1f851bc511800e6129ccd5a3542ab"; }; |
garyservin | 0:a906bb7c7831 | 184 | |
garyservin | 0:a906bb7c7831 | 185 | }; |
garyservin | 0:a906bb7c7831 | 186 | |
garyservin | 0:a906bb7c7831 | 187 | class GetPolledImage { |
garyservin | 0:a906bb7c7831 | 188 | public: |
garyservin | 0:a906bb7c7831 | 189 | typedef GetPolledImageRequest Request; |
garyservin | 0:a906bb7c7831 | 190 | typedef GetPolledImageResponse Response; |
garyservin | 0:a906bb7c7831 | 191 | }; |
garyservin | 0:a906bb7c7831 | 192 | |
garyservin | 0:a906bb7c7831 | 193 | } |
garyservin | 0:a906bb7c7831 | 194 | #endif |