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(); } }
rosgraph_msgs/Log.h@1:a849bf78d77f, 2016-12-31 (annotated)
- Committer:
- garyservin
- Date:
- Sat Dec 31 00:59:58 2016 +0000
- Revision:
- 1:a849bf78d77f
- Parent:
- 0:9e9b7db60fd5
Add missing round() method
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_rosgraph_msgs_Log_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_rosgraph_msgs_Log_h |
garyservin | 0:9e9b7db60fd5 | 3 | |
garyservin | 0:9e9b7db60fd5 | 4 | #include <stdint.h> |
garyservin | 0:9e9b7db60fd5 | 5 | #include <string.h> |
garyservin | 0:9e9b7db60fd5 | 6 | #include <stdlib.h> |
garyservin | 0:9e9b7db60fd5 | 7 | #include "ros/msg.h" |
garyservin | 0:9e9b7db60fd5 | 8 | #include "std_msgs/Header.h" |
garyservin | 0:9e9b7db60fd5 | 9 | |
garyservin | 0:9e9b7db60fd5 | 10 | namespace rosgraph_msgs |
garyservin | 0:9e9b7db60fd5 | 11 | { |
garyservin | 0:9e9b7db60fd5 | 12 | |
garyservin | 0:9e9b7db60fd5 | 13 | class Log : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 14 | { |
garyservin | 0:9e9b7db60fd5 | 15 | public: |
garyservin | 0:9e9b7db60fd5 | 16 | typedef std_msgs::Header _header_type; |
garyservin | 0:9e9b7db60fd5 | 17 | _header_type header; |
garyservin | 0:9e9b7db60fd5 | 18 | typedef int8_t _level_type; |
garyservin | 0:9e9b7db60fd5 | 19 | _level_type level; |
garyservin | 0:9e9b7db60fd5 | 20 | typedef const char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 21 | _name_type name; |
garyservin | 0:9e9b7db60fd5 | 22 | typedef const char* _msg_type; |
garyservin | 0:9e9b7db60fd5 | 23 | _msg_type msg; |
garyservin | 0:9e9b7db60fd5 | 24 | typedef const char* _file_type; |
garyservin | 0:9e9b7db60fd5 | 25 | _file_type file; |
garyservin | 0:9e9b7db60fd5 | 26 | typedef const char* _function_type; |
garyservin | 0:9e9b7db60fd5 | 27 | _function_type function; |
garyservin | 0:9e9b7db60fd5 | 28 | typedef uint32_t _line_type; |
garyservin | 0:9e9b7db60fd5 | 29 | _line_type line; |
garyservin | 0:9e9b7db60fd5 | 30 | uint32_t topics_length; |
garyservin | 0:9e9b7db60fd5 | 31 | typedef char* _topics_type; |
garyservin | 0:9e9b7db60fd5 | 32 | _topics_type st_topics; |
garyservin | 0:9e9b7db60fd5 | 33 | _topics_type * topics; |
garyservin | 0:9e9b7db60fd5 | 34 | enum { DEBUG = 1 }; |
garyservin | 0:9e9b7db60fd5 | 35 | enum { INFO = 2 }; |
garyservin | 0:9e9b7db60fd5 | 36 | enum { WARN = 4 }; |
garyservin | 0:9e9b7db60fd5 | 37 | enum { ERROR = 8 }; |
garyservin | 0:9e9b7db60fd5 | 38 | enum { FATAL = 16 }; |
garyservin | 0:9e9b7db60fd5 | 39 | |
garyservin | 0:9e9b7db60fd5 | 40 | Log(): |
garyservin | 0:9e9b7db60fd5 | 41 | header(), |
garyservin | 0:9e9b7db60fd5 | 42 | level(0), |
garyservin | 0:9e9b7db60fd5 | 43 | name(""), |
garyservin | 0:9e9b7db60fd5 | 44 | msg(""), |
garyservin | 0:9e9b7db60fd5 | 45 | file(""), |
garyservin | 0:9e9b7db60fd5 | 46 | function(""), |
garyservin | 0:9e9b7db60fd5 | 47 | line(0), |
garyservin | 0:9e9b7db60fd5 | 48 | topics_length(0), topics(NULL) |
garyservin | 0:9e9b7db60fd5 | 49 | { |
garyservin | 0:9e9b7db60fd5 | 50 | } |
garyservin | 0:9e9b7db60fd5 | 51 | |
garyservin | 0:9e9b7db60fd5 | 52 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 53 | { |
garyservin | 0:9e9b7db60fd5 | 54 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 55 | offset += this->header.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 56 | union { |
garyservin | 0:9e9b7db60fd5 | 57 | int8_t real; |
garyservin | 0:9e9b7db60fd5 | 58 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 59 | } u_level; |
garyservin | 0:9e9b7db60fd5 | 60 | u_level.real = this->level; |
garyservin | 0:9e9b7db60fd5 | 61 | *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 62 | offset += sizeof(this->level); |
garyservin | 0:9e9b7db60fd5 | 63 | uint32_t length_name = strlen(this->name); |
garyservin | 0:9e9b7db60fd5 | 64 | varToArr(outbuffer + offset, length_name); |
garyservin | 0:9e9b7db60fd5 | 65 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 66 | memcpy(outbuffer + offset, this->name, length_name); |
garyservin | 0:9e9b7db60fd5 | 67 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 68 | uint32_t length_msg = strlen(this->msg); |
garyservin | 0:9e9b7db60fd5 | 69 | varToArr(outbuffer + offset, length_msg); |
garyservin | 0:9e9b7db60fd5 | 70 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 71 | memcpy(outbuffer + offset, this->msg, length_msg); |
garyservin | 0:9e9b7db60fd5 | 72 | offset += length_msg; |
garyservin | 0:9e9b7db60fd5 | 73 | uint32_t length_file = strlen(this->file); |
garyservin | 0:9e9b7db60fd5 | 74 | varToArr(outbuffer + offset, length_file); |
garyservin | 0:9e9b7db60fd5 | 75 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 76 | memcpy(outbuffer + offset, this->file, length_file); |
garyservin | 0:9e9b7db60fd5 | 77 | offset += length_file; |
garyservin | 0:9e9b7db60fd5 | 78 | uint32_t length_function = strlen(this->function); |
garyservin | 0:9e9b7db60fd5 | 79 | varToArr(outbuffer + offset, length_function); |
garyservin | 0:9e9b7db60fd5 | 80 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 81 | memcpy(outbuffer + offset, this->function, length_function); |
garyservin | 0:9e9b7db60fd5 | 82 | offset += length_function; |
garyservin | 0:9e9b7db60fd5 | 83 | *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 84 | *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 85 | *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 86 | *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 87 | offset += sizeof(this->line); |
garyservin | 0:9e9b7db60fd5 | 88 | *(outbuffer + offset + 0) = (this->topics_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 89 | *(outbuffer + offset + 1) = (this->topics_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 90 | *(outbuffer + offset + 2) = (this->topics_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 91 | *(outbuffer + offset + 3) = (this->topics_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 92 | offset += sizeof(this->topics_length); |
garyservin | 0:9e9b7db60fd5 | 93 | for( uint32_t i = 0; i < topics_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 94 | uint32_t length_topicsi = strlen(this->topics[i]); |
garyservin | 0:9e9b7db60fd5 | 95 | varToArr(outbuffer + offset, length_topicsi); |
garyservin | 0:9e9b7db60fd5 | 96 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 97 | memcpy(outbuffer + offset, this->topics[i], length_topicsi); |
garyservin | 0:9e9b7db60fd5 | 98 | offset += length_topicsi; |
garyservin | 0:9e9b7db60fd5 | 99 | } |
garyservin | 0:9e9b7db60fd5 | 100 | return offset; |
garyservin | 0:9e9b7db60fd5 | 101 | } |
garyservin | 0:9e9b7db60fd5 | 102 | |
garyservin | 0:9e9b7db60fd5 | 103 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 104 | { |
garyservin | 0:9e9b7db60fd5 | 105 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 106 | offset += this->header.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 107 | union { |
garyservin | 0:9e9b7db60fd5 | 108 | int8_t real; |
garyservin | 0:9e9b7db60fd5 | 109 | uint8_t base; |
garyservin | 0:9e9b7db60fd5 | 110 | } u_level; |
garyservin | 0:9e9b7db60fd5 | 111 | u_level.base = 0; |
garyservin | 0:9e9b7db60fd5 | 112 | u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 113 | this->level = u_level.real; |
garyservin | 0:9e9b7db60fd5 | 114 | offset += sizeof(this->level); |
garyservin | 0:9e9b7db60fd5 | 115 | uint32_t length_name; |
garyservin | 0:9e9b7db60fd5 | 116 | arrToVar(length_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 117 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 118 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 119 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 120 | } |
garyservin | 0:9e9b7db60fd5 | 121 | inbuffer[offset+length_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 122 | this->name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 123 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 124 | uint32_t length_msg; |
garyservin | 0:9e9b7db60fd5 | 125 | arrToVar(length_msg, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 126 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 127 | for(unsigned int k= offset; k< offset+length_msg; ++k){ |
garyservin | 0:9e9b7db60fd5 | 128 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 129 | } |
garyservin | 0:9e9b7db60fd5 | 130 | inbuffer[offset+length_msg-1]=0; |
garyservin | 0:9e9b7db60fd5 | 131 | this->msg = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 132 | offset += length_msg; |
garyservin | 0:9e9b7db60fd5 | 133 | uint32_t length_file; |
garyservin | 0:9e9b7db60fd5 | 134 | arrToVar(length_file, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 135 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 136 | for(unsigned int k= offset; k< offset+length_file; ++k){ |
garyservin | 0:9e9b7db60fd5 | 137 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 138 | } |
garyservin | 0:9e9b7db60fd5 | 139 | inbuffer[offset+length_file-1]=0; |
garyservin | 0:9e9b7db60fd5 | 140 | this->file = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 141 | offset += length_file; |
garyservin | 0:9e9b7db60fd5 | 142 | uint32_t length_function; |
garyservin | 0:9e9b7db60fd5 | 143 | arrToVar(length_function, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 144 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 145 | for(unsigned int k= offset; k< offset+length_function; ++k){ |
garyservin | 0:9e9b7db60fd5 | 146 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 147 | } |
garyservin | 0:9e9b7db60fd5 | 148 | inbuffer[offset+length_function-1]=0; |
garyservin | 0:9e9b7db60fd5 | 149 | this->function = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 150 | offset += length_function; |
garyservin | 0:9e9b7db60fd5 | 151 | this->line = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 152 | this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 153 | this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 154 | this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 155 | offset += sizeof(this->line); |
garyservin | 0:9e9b7db60fd5 | 156 | uint32_t topics_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 157 | topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 158 | topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 159 | topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 160 | offset += sizeof(this->topics_length); |
garyservin | 0:9e9b7db60fd5 | 161 | if(topics_lengthT > topics_length) |
garyservin | 0:9e9b7db60fd5 | 162 | this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 163 | topics_length = topics_lengthT; |
garyservin | 0:9e9b7db60fd5 | 164 | for( uint32_t i = 0; i < topics_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 165 | uint32_t length_st_topics; |
garyservin | 0:9e9b7db60fd5 | 166 | arrToVar(length_st_topics, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 167 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 168 | for(unsigned int k= offset; k< offset+length_st_topics; ++k){ |
garyservin | 0:9e9b7db60fd5 | 169 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 170 | } |
garyservin | 0:9e9b7db60fd5 | 171 | inbuffer[offset+length_st_topics-1]=0; |
garyservin | 0:9e9b7db60fd5 | 172 | this->st_topics = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 173 | offset += length_st_topics; |
garyservin | 0:9e9b7db60fd5 | 174 | memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 175 | } |
garyservin | 0:9e9b7db60fd5 | 176 | return offset; |
garyservin | 0:9e9b7db60fd5 | 177 | } |
garyservin | 0:9e9b7db60fd5 | 178 | |
garyservin | 0:9e9b7db60fd5 | 179 | const char * getType(){ return "rosgraph_msgs/Log"; }; |
garyservin | 0:9e9b7db60fd5 | 180 | const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; }; |
garyservin | 0:9e9b7db60fd5 | 181 | |
garyservin | 0:9e9b7db60fd5 | 182 | }; |
garyservin | 0:9e9b7db60fd5 | 183 | |
garyservin | 0:9e9b7db60fd5 | 184 | } |
garyservin | 0:9e9b7db60fd5 | 185 | #endif |