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(); } }
sensor_msgs/Imu.h
- Committer:
- Gary Servin
- Date:
- 2019-11-08
- Revision:
- 0:04ac6be8229a
File content as of revision 0:04ac6be8229a:
#ifndef _ROS_sensor_msgs_Imu_h #define _ROS_sensor_msgs_Imu_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "std_msgs/Header.h" #include "geometry_msgs/Quaternion.h" #include "geometry_msgs/Vector3.h" namespace sensor_msgs { class Imu : public ros::Msg { public: typedef std_msgs::Header _header_type; _header_type header; typedef geometry_msgs::Quaternion _orientation_type; _orientation_type orientation; double orientation_covariance[9]; typedef geometry_msgs::Vector3 _angular_velocity_type; _angular_velocity_type angular_velocity; double angular_velocity_covariance[9]; typedef geometry_msgs::Vector3 _linear_acceleration_type; _linear_acceleration_type linear_acceleration; double linear_acceleration_covariance[9]; Imu(): header(), orientation(), orientation_covariance(), angular_velocity(), angular_velocity_covariance(), linear_acceleration(), linear_acceleration_covariance() { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); offset += this->orientation.serialize(outbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_orientation_covariancei; u_orientation_covariancei.real = this->orientation_covariance[i]; *(outbuffer + offset + 0) = (u_orientation_covariancei.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_orientation_covariancei.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_orientation_covariancei.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_orientation_covariancei.base >> (8 * 3)) & 0xFF; *(outbuffer + offset + 4) = (u_orientation_covariancei.base >> (8 * 4)) & 0xFF; *(outbuffer + offset + 5) = (u_orientation_covariancei.base >> (8 * 5)) & 0xFF; *(outbuffer + offset + 6) = (u_orientation_covariancei.base >> (8 * 6)) & 0xFF; *(outbuffer + offset + 7) = (u_orientation_covariancei.base >> (8 * 7)) & 0xFF; offset += sizeof(this->orientation_covariance[i]); } offset += this->angular_velocity.serialize(outbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_angular_velocity_covariancei; u_angular_velocity_covariancei.real = this->angular_velocity_covariance[i]; *(outbuffer + offset + 0) = (u_angular_velocity_covariancei.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_angular_velocity_covariancei.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_angular_velocity_covariancei.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_angular_velocity_covariancei.base >> (8 * 3)) & 0xFF; *(outbuffer + offset + 4) = (u_angular_velocity_covariancei.base >> (8 * 4)) & 0xFF; *(outbuffer + offset + 5) = (u_angular_velocity_covariancei.base >> (8 * 5)) & 0xFF; *(outbuffer + offset + 6) = (u_angular_velocity_covariancei.base >> (8 * 6)) & 0xFF; *(outbuffer + offset + 7) = (u_angular_velocity_covariancei.base >> (8 * 7)) & 0xFF; offset += sizeof(this->angular_velocity_covariance[i]); } offset += this->linear_acceleration.serialize(outbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_linear_acceleration_covariancei; u_linear_acceleration_covariancei.real = this->linear_acceleration_covariance[i]; *(outbuffer + offset + 0) = (u_linear_acceleration_covariancei.base >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (u_linear_acceleration_covariancei.base >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (u_linear_acceleration_covariancei.base >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (u_linear_acceleration_covariancei.base >> (8 * 3)) & 0xFF; *(outbuffer + offset + 4) = (u_linear_acceleration_covariancei.base >> (8 * 4)) & 0xFF; *(outbuffer + offset + 5) = (u_linear_acceleration_covariancei.base >> (8 * 5)) & 0xFF; *(outbuffer + offset + 6) = (u_linear_acceleration_covariancei.base >> (8 * 6)) & 0xFF; *(outbuffer + offset + 7) = (u_linear_acceleration_covariancei.base >> (8 * 7)) & 0xFF; offset += sizeof(this->linear_acceleration_covariance[i]); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->header.deserialize(inbuffer + offset); offset += this->orientation.deserialize(inbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_orientation_covariancei; u_orientation_covariancei.base = 0; u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); u_orientation_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); this->orientation_covariance[i] = u_orientation_covariancei.real; offset += sizeof(this->orientation_covariance[i]); } offset += this->angular_velocity.deserialize(inbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_angular_velocity_covariancei; u_angular_velocity_covariancei.base = 0; u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); u_angular_velocity_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); this->angular_velocity_covariance[i] = u_angular_velocity_covariancei.real; offset += sizeof(this->angular_velocity_covariance[i]); } offset += this->linear_acceleration.deserialize(inbuffer + offset); for( uint32_t i = 0; i < 9; i++){ union { double real; uint64_t base; } u_linear_acceleration_covariancei; u_linear_acceleration_covariancei.base = 0; u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); u_linear_acceleration_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); this->linear_acceleration_covariance[i] = u_linear_acceleration_covariancei.real; offset += sizeof(this->linear_acceleration_covariance[i]); } return offset; } const char * getType(){ return "sensor_msgs/Imu"; }; const char * getMD5(){ return "6a62c6daae103f4ff57a132d6f95cec2"; }; }; } #endif