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(); } }
control_msgs/JointTrajectoryControllerState.h@1:da82487f547e, 2019-11-08 (annotated)
- Committer:
- Gary Servin
- Date:
- Fri Nov 08 14:55:04 2019 -0300
- Revision:
- 1:da82487f547e
- Parent:
- 0:04ac6be8229a
Add missing round() method
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
Gary Servin |
0:04ac6be8229a | 1 | #ifndef _ROS_control_msgs_JointTrajectoryControllerState_h |
Gary Servin |
0:04ac6be8229a | 2 | #define _ROS_control_msgs_JointTrajectoryControllerState_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 "std_msgs/Header.h" |
Gary Servin |
0:04ac6be8229a | 9 | #include "trajectory_msgs/JointTrajectoryPoint.h" |
Gary Servin |
0:04ac6be8229a | 10 | |
Gary Servin |
0:04ac6be8229a | 11 | namespace control_msgs |
Gary Servin |
0:04ac6be8229a | 12 | { |
Gary Servin |
0:04ac6be8229a | 13 | |
Gary Servin |
0:04ac6be8229a | 14 | class JointTrajectoryControllerState : public ros::Msg |
Gary Servin |
0:04ac6be8229a | 15 | { |
Gary Servin |
0:04ac6be8229a | 16 | public: |
Gary Servin |
0:04ac6be8229a | 17 | typedef std_msgs::Header _header_type; |
Gary Servin |
0:04ac6be8229a | 18 | _header_type header; |
Gary Servin |
0:04ac6be8229a | 19 | uint32_t joint_names_length; |
Gary Servin |
0:04ac6be8229a | 20 | typedef char* _joint_names_type; |
Gary Servin |
0:04ac6be8229a | 21 | _joint_names_type st_joint_names; |
Gary Servin |
0:04ac6be8229a | 22 | _joint_names_type * joint_names; |
Gary Servin |
0:04ac6be8229a | 23 | typedef trajectory_msgs::JointTrajectoryPoint _desired_type; |
Gary Servin |
0:04ac6be8229a | 24 | _desired_type desired; |
Gary Servin |
0:04ac6be8229a | 25 | typedef trajectory_msgs::JointTrajectoryPoint _actual_type; |
Gary Servin |
0:04ac6be8229a | 26 | _actual_type actual; |
Gary Servin |
0:04ac6be8229a | 27 | typedef trajectory_msgs::JointTrajectoryPoint _error_type; |
Gary Servin |
0:04ac6be8229a | 28 | _error_type error; |
Gary Servin |
0:04ac6be8229a | 29 | |
Gary Servin |
0:04ac6be8229a | 30 | JointTrajectoryControllerState(): |
Gary Servin |
0:04ac6be8229a | 31 | header(), |
Gary Servin |
0:04ac6be8229a | 32 | joint_names_length(0), joint_names(NULL), |
Gary Servin |
0:04ac6be8229a | 33 | desired(), |
Gary Servin |
0:04ac6be8229a | 34 | actual(), |
Gary Servin |
0:04ac6be8229a | 35 | error() |
Gary Servin |
0:04ac6be8229a | 36 | { |
Gary Servin |
0:04ac6be8229a | 37 | } |
Gary Servin |
0:04ac6be8229a | 38 | |
Gary Servin |
0:04ac6be8229a | 39 | virtual int serialize(unsigned char *outbuffer) const |
Gary Servin |
0:04ac6be8229a | 40 | { |
Gary Servin |
0:04ac6be8229a | 41 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 42 | offset += this->header.serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 43 | *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 44 | *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 45 | *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 46 | *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF; |
Gary Servin |
0:04ac6be8229a | 47 | offset += sizeof(this->joint_names_length); |
Gary Servin |
0:04ac6be8229a | 48 | for( uint32_t i = 0; i < joint_names_length; i++){ |
Gary Servin |
0:04ac6be8229a | 49 | uint32_t length_joint_namesi = strlen(this->joint_names[i]); |
Gary Servin |
0:04ac6be8229a | 50 | varToArr(outbuffer + offset, length_joint_namesi); |
Gary Servin |
0:04ac6be8229a | 51 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 52 | memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi); |
Gary Servin |
0:04ac6be8229a | 53 | offset += length_joint_namesi; |
Gary Servin |
0:04ac6be8229a | 54 | } |
Gary Servin |
0:04ac6be8229a | 55 | offset += this->desired.serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 56 | offset += this->actual.serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 57 | offset += this->error.serialize(outbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 58 | return offset; |
Gary Servin |
0:04ac6be8229a | 59 | } |
Gary Servin |
0:04ac6be8229a | 60 | |
Gary Servin |
0:04ac6be8229a | 61 | virtual int deserialize(unsigned char *inbuffer) |
Gary Servin |
0:04ac6be8229a | 62 | { |
Gary Servin |
0:04ac6be8229a | 63 | int offset = 0; |
Gary Servin |
0:04ac6be8229a | 64 | offset += this->header.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 65 | uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset))); |
Gary Servin |
0:04ac6be8229a | 66 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
Gary Servin |
0:04ac6be8229a | 67 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
Gary Servin |
0:04ac6be8229a | 68 | joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
Gary Servin |
0:04ac6be8229a | 69 | offset += sizeof(this->joint_names_length); |
Gary Servin |
0:04ac6be8229a | 70 | if(joint_names_lengthT > joint_names_length) |
Gary Servin |
0:04ac6be8229a | 71 | this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*)); |
Gary Servin |
0:04ac6be8229a | 72 | joint_names_length = joint_names_lengthT; |
Gary Servin |
0:04ac6be8229a | 73 | for( uint32_t i = 0; i < joint_names_length; i++){ |
Gary Servin |
0:04ac6be8229a | 74 | uint32_t length_st_joint_names; |
Gary Servin |
0:04ac6be8229a | 75 | arrToVar(length_st_joint_names, (inbuffer + offset)); |
Gary Servin |
0:04ac6be8229a | 76 | offset += 4; |
Gary Servin |
0:04ac6be8229a | 77 | for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){ |
Gary Servin |
0:04ac6be8229a | 78 | inbuffer[k-1]=inbuffer[k]; |
Gary Servin |
0:04ac6be8229a | 79 | } |
Gary Servin |
0:04ac6be8229a | 80 | inbuffer[offset+length_st_joint_names-1]=0; |
Gary Servin |
0:04ac6be8229a | 81 | this->st_joint_names = (char *)(inbuffer + offset-1); |
Gary Servin |
0:04ac6be8229a | 82 | offset += length_st_joint_names; |
Gary Servin |
0:04ac6be8229a | 83 | memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*)); |
Gary Servin |
0:04ac6be8229a | 84 | } |
Gary Servin |
0:04ac6be8229a | 85 | offset += this->desired.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 86 | offset += this->actual.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 87 | offset += this->error.deserialize(inbuffer + offset); |
Gary Servin |
0:04ac6be8229a | 88 | return offset; |
Gary Servin |
0:04ac6be8229a | 89 | } |
Gary Servin |
0:04ac6be8229a | 90 | |
Gary Servin |
0:04ac6be8229a | 91 | const char * getType(){ return "control_msgs/JointTrajectoryControllerState"; }; |
Gary Servin |
0:04ac6be8229a | 92 | const char * getMD5(){ return "10817c60c2486ef6b33e97dcd87f4474"; }; |
Gary Servin |
0:04ac6be8229a | 93 | |
Gary Servin |
0:04ac6be8229a | 94 | }; |
Gary Servin |
0:04ac6be8229a | 95 | |
Gary Servin |
0:04ac6be8229a | 96 | } |
Gary Servin |
0:04ac6be8229a | 97 | #endif |