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(); } }
Diff: controller_manager_msgs/LoadController.h
- Revision:
- 0:04ac6be8229a
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/controller_manager_msgs/LoadController.h Fri Nov 08 14:38:09 2019 -0300 @@ -0,0 +1,105 @@ +#ifndef _ROS_SERVICE_LoadController_h +#define _ROS_SERVICE_LoadController_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace controller_manager_msgs +{ + +static const char LOADCONTROLLER[] = "controller_manager_msgs/LoadController"; + + class LoadControllerRequest : public ros::Msg + { + public: + typedef const char* _name_type; + _name_type name; + + LoadControllerRequest(): + name("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + uint32_t length_name = strlen(this->name); + varToArr(outbuffer + offset, length_name); + offset += 4; + memcpy(outbuffer + offset, this->name, length_name); + offset += length_name; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + uint32_t length_name; + arrToVar(length_name, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_name; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_name-1]=0; + this->name = (char *)(inbuffer + offset-1); + offset += length_name; + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "c1f3d28f1b044c871e6eff2e9fc3c667"; }; + + }; + + class LoadControllerResponse : public ros::Msg + { + public: + typedef bool _ok_type; + _ok_type ok; + + LoadControllerResponse(): + ok(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.real = this->ok; + *(outbuffer + offset + 0) = (u_ok.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->ok); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_ok; + u_ok.base = 0; + u_ok.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->ok = u_ok.real; + offset += sizeof(this->ok); + return offset; + } + + const char * getType(){ return LOADCONTROLLER; }; + const char * getMD5(){ return "6f6da3883749771fac40d6deb24a8c02"; }; + + }; + + class LoadController { + public: + typedef LoadControllerRequest Request; + typedef LoadControllerResponse Response; + }; + +} +#endif