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(); } }
visualization_msgs/InteractiveMarkerUpdate.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_visualization_msgs_InteractiveMarkerUpdate_h |
garyservin | 0:a906bb7c7831 | 2 | #define _ROS_visualization_msgs_InteractiveMarkerUpdate_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 "visualization_msgs/InteractiveMarker.h" |
garyservin | 0:a906bb7c7831 | 9 | #include "visualization_msgs/InteractiveMarkerPose.h" |
garyservin | 0:a906bb7c7831 | 10 | |
garyservin | 0:a906bb7c7831 | 11 | namespace visualization_msgs |
garyservin | 0:a906bb7c7831 | 12 | { |
garyservin | 0:a906bb7c7831 | 13 | |
garyservin | 0:a906bb7c7831 | 14 | class InteractiveMarkerUpdate : public ros::Msg |
garyservin | 0:a906bb7c7831 | 15 | { |
garyservin | 0:a906bb7c7831 | 16 | public: |
garyservin | 0:a906bb7c7831 | 17 | const char* server_id; |
garyservin | 0:a906bb7c7831 | 18 | uint64_t seq_num; |
garyservin | 0:a906bb7c7831 | 19 | uint8_t type; |
garyservin | 0:a906bb7c7831 | 20 | uint8_t markers_length; |
garyservin | 0:a906bb7c7831 | 21 | visualization_msgs::InteractiveMarker st_markers; |
garyservin | 0:a906bb7c7831 | 22 | visualization_msgs::InteractiveMarker * markers; |
garyservin | 0:a906bb7c7831 | 23 | uint8_t poses_length; |
garyservin | 0:a906bb7c7831 | 24 | visualization_msgs::InteractiveMarkerPose st_poses; |
garyservin | 0:a906bb7c7831 | 25 | visualization_msgs::InteractiveMarkerPose * poses; |
garyservin | 0:a906bb7c7831 | 26 | uint8_t erases_length; |
garyservin | 0:a906bb7c7831 | 27 | char* st_erases; |
garyservin | 0:a906bb7c7831 | 28 | char* * erases; |
garyservin | 0:a906bb7c7831 | 29 | enum { KEEP_ALIVE = 0 }; |
garyservin | 0:a906bb7c7831 | 30 | enum { UPDATE = 1 }; |
garyservin | 0:a906bb7c7831 | 31 | |
garyservin | 0:a906bb7c7831 | 32 | InteractiveMarkerUpdate(): |
garyservin | 0:a906bb7c7831 | 33 | server_id(""), |
garyservin | 0:a906bb7c7831 | 34 | seq_num(0), |
garyservin | 0:a906bb7c7831 | 35 | type(0), |
garyservin | 0:a906bb7c7831 | 36 | markers_length(0), markers(NULL), |
garyservin | 0:a906bb7c7831 | 37 | poses_length(0), poses(NULL), |
garyservin | 0:a906bb7c7831 | 38 | erases_length(0), erases(NULL) |
garyservin | 0:a906bb7c7831 | 39 | { |
garyservin | 0:a906bb7c7831 | 40 | } |
garyservin | 0:a906bb7c7831 | 41 | |
garyservin | 0:a906bb7c7831 | 42 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:a906bb7c7831 | 43 | { |
garyservin | 0:a906bb7c7831 | 44 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 45 | uint32_t length_server_id = strlen(this->server_id); |
garyservin | 0:a906bb7c7831 | 46 | memcpy(outbuffer + offset, &length_server_id, sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 47 | offset += 4; |
garyservin | 0:a906bb7c7831 | 48 | memcpy(outbuffer + offset, this->server_id, length_server_id); |
garyservin | 0:a906bb7c7831 | 49 | offset += length_server_id; |
garyservin | 0:a906bb7c7831 | 50 | union { |
garyservin | 0:a906bb7c7831 | 51 | uint64_t real; |
garyservin | 0:a906bb7c7831 | 52 | uint32_t base; |
garyservin | 0:a906bb7c7831 | 53 | } u_seq_num; |
garyservin | 0:a906bb7c7831 | 54 | u_seq_num.real = this->seq_num; |
garyservin | 0:a906bb7c7831 | 55 | *(outbuffer + offset + 0) = (u_seq_num.base >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 56 | *(outbuffer + offset + 1) = (u_seq_num.base >> (8 * 1)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 57 | *(outbuffer + offset + 2) = (u_seq_num.base >> (8 * 2)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 58 | *(outbuffer + offset + 3) = (u_seq_num.base >> (8 * 3)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 59 | offset += sizeof(this->seq_num); |
garyservin | 0:a906bb7c7831 | 60 | *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; |
garyservin | 0:a906bb7c7831 | 61 | offset += sizeof(this->type); |
garyservin | 0:a906bb7c7831 | 62 | *(outbuffer + offset++) = markers_length; |
garyservin | 0:a906bb7c7831 | 63 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 64 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 65 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 66 | for( uint8_t i = 0; i < markers_length; i++){ |
garyservin | 0:a906bb7c7831 | 67 | offset += this->markers[i].serialize(outbuffer + offset); |
garyservin | 0:a906bb7c7831 | 68 | } |
garyservin | 0:a906bb7c7831 | 69 | *(outbuffer + offset++) = poses_length; |
garyservin | 0:a906bb7c7831 | 70 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 71 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 72 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 73 | for( uint8_t i = 0; i < poses_length; i++){ |
garyservin | 0:a906bb7c7831 | 74 | offset += this->poses[i].serialize(outbuffer + offset); |
garyservin | 0:a906bb7c7831 | 75 | } |
garyservin | 0:a906bb7c7831 | 76 | *(outbuffer + offset++) = erases_length; |
garyservin | 0:a906bb7c7831 | 77 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 78 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 79 | *(outbuffer + offset++) = 0; |
garyservin | 0:a906bb7c7831 | 80 | for( uint8_t i = 0; i < erases_length; i++){ |
garyservin | 0:a906bb7c7831 | 81 | uint32_t length_erasesi = strlen(this->erases[i]); |
garyservin | 0:a906bb7c7831 | 82 | memcpy(outbuffer + offset, &length_erasesi, sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 83 | offset += 4; |
garyservin | 0:a906bb7c7831 | 84 | memcpy(outbuffer + offset, this->erases[i], length_erasesi); |
garyservin | 0:a906bb7c7831 | 85 | offset += length_erasesi; |
garyservin | 0:a906bb7c7831 | 86 | } |
garyservin | 0:a906bb7c7831 | 87 | return offset; |
garyservin | 0:a906bb7c7831 | 88 | } |
garyservin | 0:a906bb7c7831 | 89 | |
garyservin | 0:a906bb7c7831 | 90 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:a906bb7c7831 | 91 | { |
garyservin | 0:a906bb7c7831 | 92 | int offset = 0; |
garyservin | 0:a906bb7c7831 | 93 | uint32_t length_server_id; |
garyservin | 0:a906bb7c7831 | 94 | memcpy(&length_server_id, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 95 | offset += 4; |
garyservin | 0:a906bb7c7831 | 96 | for(unsigned int k= offset; k< offset+length_server_id; ++k){ |
garyservin | 0:a906bb7c7831 | 97 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:a906bb7c7831 | 98 | } |
garyservin | 0:a906bb7c7831 | 99 | inbuffer[offset+length_server_id-1]=0; |
garyservin | 0:a906bb7c7831 | 100 | this->server_id = (char *)(inbuffer + offset-1); |
garyservin | 0:a906bb7c7831 | 101 | offset += length_server_id; |
garyservin | 0:a906bb7c7831 | 102 | union { |
garyservin | 0:a906bb7c7831 | 103 | uint64_t real; |
garyservin | 0:a906bb7c7831 | 104 | uint32_t base; |
garyservin | 0:a906bb7c7831 | 105 | } u_seq_num; |
garyservin | 0:a906bb7c7831 | 106 | u_seq_num.base = 0; |
garyservin | 0:a906bb7c7831 | 107 | u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:a906bb7c7831 | 108 | u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:a906bb7c7831 | 109 | u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:a906bb7c7831 | 110 | u_seq_num.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:a906bb7c7831 | 111 | this->seq_num = u_seq_num.real; |
garyservin | 0:a906bb7c7831 | 112 | offset += sizeof(this->seq_num); |
garyservin | 0:a906bb7c7831 | 113 | this->type = ((uint8_t) (*(inbuffer + offset))); |
garyservin | 0:a906bb7c7831 | 114 | offset += sizeof(this->type); |
garyservin | 0:a906bb7c7831 | 115 | uint8_t markers_lengthT = *(inbuffer + offset++); |
garyservin | 0:a906bb7c7831 | 116 | if(markers_lengthT > markers_length) |
garyservin | 0:a906bb7c7831 | 117 | this->markers = (visualization_msgs::InteractiveMarker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::InteractiveMarker)); |
garyservin | 0:a906bb7c7831 | 118 | offset += 3; |
garyservin | 0:a906bb7c7831 | 119 | markers_length = markers_lengthT; |
garyservin | 0:a906bb7c7831 | 120 | for( uint8_t i = 0; i < markers_length; i++){ |
garyservin | 0:a906bb7c7831 | 121 | offset += this->st_markers.deserialize(inbuffer + offset); |
garyservin | 0:a906bb7c7831 | 122 | memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::InteractiveMarker)); |
garyservin | 0:a906bb7c7831 | 123 | } |
garyservin | 0:a906bb7c7831 | 124 | uint8_t poses_lengthT = *(inbuffer + offset++); |
garyservin | 0:a906bb7c7831 | 125 | if(poses_lengthT > poses_length) |
garyservin | 0:a906bb7c7831 | 126 | this->poses = (visualization_msgs::InteractiveMarkerPose*)realloc(this->poses, poses_lengthT * sizeof(visualization_msgs::InteractiveMarkerPose)); |
garyservin | 0:a906bb7c7831 | 127 | offset += 3; |
garyservin | 0:a906bb7c7831 | 128 | poses_length = poses_lengthT; |
garyservin | 0:a906bb7c7831 | 129 | for( uint8_t i = 0; i < poses_length; i++){ |
garyservin | 0:a906bb7c7831 | 130 | offset += this->st_poses.deserialize(inbuffer + offset); |
garyservin | 0:a906bb7c7831 | 131 | memcpy( &(this->poses[i]), &(this->st_poses), sizeof(visualization_msgs::InteractiveMarkerPose)); |
garyservin | 0:a906bb7c7831 | 132 | } |
garyservin | 0:a906bb7c7831 | 133 | uint8_t erases_lengthT = *(inbuffer + offset++); |
garyservin | 0:a906bb7c7831 | 134 | if(erases_lengthT > erases_length) |
garyservin | 0:a906bb7c7831 | 135 | this->erases = (char**)realloc(this->erases, erases_lengthT * sizeof(char*)); |
garyservin | 0:a906bb7c7831 | 136 | offset += 3; |
garyservin | 0:a906bb7c7831 | 137 | erases_length = erases_lengthT; |
garyservin | 0:a906bb7c7831 | 138 | for( uint8_t i = 0; i < erases_length; i++){ |
garyservin | 0:a906bb7c7831 | 139 | uint32_t length_st_erases; |
garyservin | 0:a906bb7c7831 | 140 | memcpy(&length_st_erases, (inbuffer + offset), sizeof(uint32_t)); |
garyservin | 0:a906bb7c7831 | 141 | offset += 4; |
garyservin | 0:a906bb7c7831 | 142 | for(unsigned int k= offset; k< offset+length_st_erases; ++k){ |
garyservin | 0:a906bb7c7831 | 143 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:a906bb7c7831 | 144 | } |
garyservin | 0:a906bb7c7831 | 145 | inbuffer[offset+length_st_erases-1]=0; |
garyservin | 0:a906bb7c7831 | 146 | this->st_erases = (char *)(inbuffer + offset-1); |
garyservin | 0:a906bb7c7831 | 147 | offset += length_st_erases; |
garyservin | 0:a906bb7c7831 | 148 | memcpy( &(this->erases[i]), &(this->st_erases), sizeof(char*)); |
garyservin | 0:a906bb7c7831 | 149 | } |
garyservin | 0:a906bb7c7831 | 150 | return offset; |
garyservin | 0:a906bb7c7831 | 151 | } |
garyservin | 0:a906bb7c7831 | 152 | |
garyservin | 0:a906bb7c7831 | 153 | const char * getType(){ return "visualization_msgs/InteractiveMarkerUpdate"; }; |
garyservin | 0:a906bb7c7831 | 154 | const char * getMD5(){ return "710d308d0a9276d65945e92dd30b3946"; }; |
garyservin | 0:a906bb7c7831 | 155 | |
garyservin | 0:a906bb7c7831 | 156 | }; |
garyservin | 0:a906bb7c7831 | 157 | |
garyservin | 0:a906bb7c7831 | 158 | } |
garyservin | 0:a906bb7c7831 | 159 | #endif |