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(); } }
geometry_msgs/PoseArray.h
- Committer:
- Gary Servin
- Date:
- 2019-11-08
- Revision:
- 0:04ac6be8229a
File content as of revision 0:04ac6be8229a:
#ifndef _ROS_geometry_msgs_PoseArray_h #define _ROS_geometry_msgs_PoseArray_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "std_msgs/Header.h" #include "geometry_msgs/Pose.h" namespace geometry_msgs { class PoseArray : public ros::Msg { public: typedef std_msgs::Header _header_type; _header_type header; uint32_t poses_length; typedef geometry_msgs::Pose _poses_type; _poses_type st_poses; _poses_type * poses; PoseArray(): header(), poses_length(0), poses(NULL) { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); *(outbuffer + offset + 0) = (this->poses_length >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (this->poses_length >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (this->poses_length >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (this->poses_length >> (8 * 3)) & 0xFF; offset += sizeof(this->poses_length); for( uint32_t i = 0; i < poses_length; i++){ offset += this->poses[i].serialize(outbuffer + offset); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->header.deserialize(inbuffer + offset); uint32_t poses_lengthT = ((uint32_t) (*(inbuffer + offset))); poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); poses_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->poses_length); if(poses_lengthT > poses_length) this->poses = (geometry_msgs::Pose*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::Pose)); poses_length = poses_lengthT; for( uint32_t i = 0; i < poses_length; i++){ offset += this->st_poses.deserialize(inbuffer + offset); memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::Pose)); } return offset; } const char * getType(){ return "geometry_msgs/PoseArray"; }; const char * getMD5(){ return "916c28c5764443f268b296bb671b9d97"; }; }; } #endif