ROS Serial library for Mbed platforms for ROS Melodic Morenia. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_melodic Motortest Nucleo_vr_servo_project NucleoFM ... more
ROSSerial_mbed for Melodic 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_melodic
rosserial_mbed Hello World example for Melodic Morenia 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(); } }
gazebo_msgs/ModelStates.h@0:04ac6be8229a, 2019-11-08 (annotated)
- Committer:
- Gary Servin
- Date:
- Fri Nov 08 14:38:09 2019 -0300
- Revision:
- 0:04ac6be8229a
Initial commit, generated based on a clean melodic-desktop-full
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
Gary Servin |
0:04ac6be8229a | 1 | #ifndef _ROS_gazebo_msgs_ModelStates_h |
Gary Servin |
0:04ac6be8229a | 2 | #define _ROS_gazebo_msgs_ModelStates_h |
Gary Servin |
0:04ac6be8229a | 3 | |
Gary Servin |
0:04ac6be8229a | 4 | #include <stdint.h> |
Gary Servin |
0:04ac6be8229a | 5 | #include <string.h> |
Gary Servin |
0:04ac6be8229a | 6 | #include <stdlib.h> |
Gary Servin |
0:04ac6be8229a | 7 | #include "ros/msg.h" |
Gary Servin |
0:04ac6be8229a | 8 | #include "geometry_msgs/Pose.h" |
Gary Servin |
0:04ac6be8229a | 9 | #include "geometry_msgs/Twist.h" |
Gary Servin |
0:04ac6be8229a | 10 | |
Gary Servin |
0:04ac6be8229a | 11 | namespace gazebo_msgs |
Gary Servin |
0:04ac6be8229a | 12 | { |
Gary Servin |
0:04ac6be8229a | 13 | |
Gary Servin |
0:04ac6be8229a | 14 | class ModelStates : public ros::Msg |
Gary Servin |
0:04ac6be8229a | 15 | { |
Gary Servin |
0:04ac6be8229a | 16 | public: |
Gary Servin |
0:04ac6be8229a | 17 | uint32_t name_length; |
Gary Servin |
0:04ac6be8229a | 18 | typedef char* _name_type; |
Gary Servin |
0:04ac6be8229a | 19 | _name_type st_name; |
Gary Servin |
0:04ac6be8229a | 20 | _name_type * name; |
Gary Servin |
0:04ac6be8229a | 21 | uint32_t pose_length; |
Gary Servin |
0:04ac6be8229a | 22 | typedef geometry_msgs::Pose _pose_type; |
Gary Servin |
0:04ac6be8229a | 23 | _pose_type st_pose; |
Gary Servin |
0:04ac6be8229a | 24 | _pose_type * pose; |
Gary Servin |
0:04ac6be8229a | 25 | uint32_t twist_length; |
Gary Servin |
0:04ac6be8229a | 26 | typedef geometry_msgs::Twist _twist_type; |
Gary Servin |
0:04ac6be8229a | 27 | _twist_type st_twist; |
Gary Servin |
0:04ac6be8229a | 28 | _twist_type * twist; |
Gary Servin |
0:04ac6be8229a | 29 | |
Gary Servin |
0:04ac6be8229a | 30 | ModelStates(): |
Gary Servin |
0:04ac6be8229a | 31 | name_length(0), name(NULL), |
Gary Servin |
0:04ac6be8229a | 32 | pose_length(0), pose(NULL), |
Gary Servin |
0:04ac6be8229a | 33 | twist_length(0), twist(NULL) |
Gary Servin |
0:04ac6be8229a | 34 | { |
Gary Servin |
0:04ac6be8229a | 35 | } |
Gary Servin |
0:04ac6be8229a | 36 | |
Gary Servin |
0:04ac6be8229a | 37 | virtual int serialize(unsigned char *outbuffer) const |
Gary Servin |
0:04ac6be8229a | 38 | { |
Gary Servin |
0:04ac6be8229a | 39 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 40 | *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 41 | *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 42 | *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 43 | *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 44 | offset += sizeof(this->name_length); |
Gary Servin |
0:04ac6be8229a | 45 | for( uint32_t i = 0; i < name_length; i++){ |
Gary Servin |
0:04ac6be8229a | 46 | uint32_t length_namei = strlen(this->name[i]); |
Gary Servin |
0:04ac6be8229a | 47 | varToArr(outbuffer + offset, length_namei); |
Gary Servin |
0:04ac6be8229a | 48 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 49 | memcpy(outbuffer + offset, this->name[i], length_namei); |
Gary Servin |
0:04ac6be8229a | 50 | offset += length_namei; |
Gary Servin |
0:04ac6be8229a | 51 | } |
Gary Servin |
0:04ac6be8229a | 52 | *(outbuffer + offset + 0) = (this->pose_length >> (8 * 0)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 53 | *(outbuffer + offset + 1) = (this->pose_length >> (8 * 1)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 54 | *(outbuffer + offset + 2) = (this->pose_length >> (8 * 2)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 55 | *(outbuffer + offset + 3) = (this->pose_length >> (8 * 3)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 56 | offset += sizeof(this->pose_length); |
Gary Servin |
0:04ac6be8229a | 57 | for( uint32_t i = 0; i < pose_length; i++){ |
Gary Servin |
0:04ac6be8229a | 58 | offset += this->pose[i].serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 59 | } |
Gary Servin |
0:04ac6be8229a | 60 | *(outbuffer + offset + 0) = (this->twist_length >> (8 * 0)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 61 | *(outbuffer + offset + 1) = (this->twist_length >> (8 * 1)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 62 | *(outbuffer + offset + 2) = (this->twist_length >> (8 * 2)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 63 | *(outbuffer + offset + 3) = (this->twist_length >> (8 * 3)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 64 | offset += sizeof(this->twist_length); |
Gary Servin |
0:04ac6be8229a | 65 | for( uint32_t i = 0; i < twist_length; i++){ |
Gary Servin |
0:04ac6be8229a | 66 | offset += this->twist[i].serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 67 | } |
Gary Servin |
0:04ac6be8229a | 68 | return offset; |
Gary Servin |
0:04ac6be8229a | 69 | } |
Gary Servin |
0:04ac6be8229a | 70 | |
Gary Servin |
0:04ac6be8229a | 71 | virtual int deserialize(unsigned char *inbuffer) |
Gary Servin |
0:04ac6be8229a | 72 | { |
Gary Servin |
0:04ac6be8229a | 73 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 74 | uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); |
Gary Servin |
0:04ac6be8229a | 75 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
Gary Servin |
0:04ac6be8229a | 76 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
Gary Servin |
0:04ac6be8229a | 77 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
Gary Servin |
0:04ac6be8229a | 78 | offset += sizeof(this->name_length); |
Gary Servin |
0:04ac6be8229a | 79 | if(name_lengthT > name_length) |
Gary Servin |
0:04ac6be8229a | 80 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
Gary Servin |
0:04ac6be8229a | 81 | name_length = name_lengthT; |
Gary Servin |
0:04ac6be8229a | 82 | for( uint32_t i = 0; i < name_length; i++){ |
Gary Servin |
0:04ac6be8229a | 83 | uint32_t length_st_name; |
Gary Servin |
0:04ac6be8229a | 84 | arrToVar(length_st_name, (inbuffer + offset)); |
Gary Servin |
0:04ac6be8229a | 85 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 86 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
Gary Servin |
0:04ac6be8229a | 87 | inbuffer[k-1]=inbuffer[k]; |
Gary Servin |
0:04ac6be8229a | 88 | } |
Gary Servin |
0:04ac6be8229a | 89 | inbuffer[offset+length_st_name-1]=0; |
Gary Servin |
0:04ac6be8229a | 90 | this->st_name = (char *)(inbuffer + offset-1); |
Gary Servin |
0:04ac6be8229a | 91 | offset += length_st_name; |
Gary Servin |
0:04ac6be8229a | 92 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
Gary Servin |
0:04ac6be8229a | 93 | } |
Gary Servin |
0:04ac6be8229a | 94 | uint32_t pose_lengthT = ((uint32_t) (*(inbuffer + offset))); |
Gary Servin |
0:04ac6be8229a | 95 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
Gary Servin |
0:04ac6be8229a | 96 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
Gary Servin |
0:04ac6be8229a | 97 | pose_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
Gary Servin |
0:04ac6be8229a | 98 | offset += sizeof(this->pose_length); |
Gary Servin |
0:04ac6be8229a | 99 | if(pose_lengthT > pose_length) |
Gary Servin |
0:04ac6be8229a | 100 | this->pose = (geometry_msgs::Pose*)realloc(this->pose, pose_lengthT * sizeof(geometry_msgs::Pose)); |
Gary Servin |
0:04ac6be8229a | 101 | pose_length = pose_lengthT; |
Gary Servin |
0:04ac6be8229a | 102 | for( uint32_t i = 0; i < pose_length; i++){ |
Gary Servin |
0:04ac6be8229a | 103 | offset += this->st_pose.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 104 | memcpy( &(this->pose[i]), &(this->st_pose), sizeof(geometry_msgs::Pose)); |
Gary Servin |
0:04ac6be8229a | 105 | } |
Gary Servin |
0:04ac6be8229a | 106 | uint32_t twist_lengthT = ((uint32_t) (*(inbuffer + offset))); |
Gary Servin |
0:04ac6be8229a | 107 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
Gary Servin |
0:04ac6be8229a | 108 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
Gary Servin |
0:04ac6be8229a | 109 | twist_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
Gary Servin |
0:04ac6be8229a | 110 | offset += sizeof(this->twist_length); |
Gary Servin |
0:04ac6be8229a | 111 | if(twist_lengthT > twist_length) |
Gary Servin |
0:04ac6be8229a | 112 | this->twist = (geometry_msgs::Twist*)realloc(this->twist, twist_lengthT * sizeof(geometry_msgs::Twist)); |
Gary Servin |
0:04ac6be8229a | 113 | twist_length = twist_lengthT; |
Gary Servin |
0:04ac6be8229a | 114 | for( uint32_t i = 0; i < twist_length; i++){ |
Gary Servin |
0:04ac6be8229a | 115 | offset += this->st_twist.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 116 | memcpy( &(this->twist[i]), &(this->st_twist), sizeof(geometry_msgs::Twist)); |
Gary Servin |
0:04ac6be8229a | 117 | } |
Gary Servin |
0:04ac6be8229a | 118 | return offset; |
Gary Servin |
0:04ac6be8229a | 119 | } |
Gary Servin |
0:04ac6be8229a | 120 | |
Gary Servin |
0:04ac6be8229a | 121 | const char * getType(){ return "gazebo_msgs/ModelStates"; }; |
Gary Servin |
0:04ac6be8229a | 122 | const char * getMD5(){ return "48c080191eb15c41858319b4d8a609c2"; }; |
Gary Servin |
0:04ac6be8229a | 123 | |
Gary Servin |
0:04ac6be8229a | 124 | }; |
Gary Servin |
0:04ac6be8229a | 125 | |
Gary Servin |
0:04ac6be8229a | 126 | } |
Gary Servin |
0:04ac6be8229a | 127 | #endif |