ROS Serial library for Mbed platforms for ROS Jade Turtle. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_jade
ROSSerial_mbed for Jade 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_jade
rosserial_mbed Hello World example for jade 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(); } }
diagnostic_msgs/DiagnosticStatus.h
- Committer:
- garyservin
- Date:
- 2016-03-31
- Revision:
- 0:a906bb7c7831
File content as of revision 0:a906bb7c7831:
#ifndef _ROS_diagnostic_msgs_DiagnosticStatus_h #define _ROS_diagnostic_msgs_DiagnosticStatus_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "diagnostic_msgs/KeyValue.h" namespace diagnostic_msgs { class DiagnosticStatus : public ros::Msg { public: int8_t level; const char* name; const char* message; const char* hardware_id; uint8_t values_length; diagnostic_msgs::KeyValue st_values; diagnostic_msgs::KeyValue * values; enum { OK = 0 }; enum { WARN = 1 }; enum { ERROR = 2 }; enum { STALE = 3 }; DiagnosticStatus(): level(0), name(""), message(""), hardware_id(""), values_length(0), values(NULL) { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; union { int8_t real; uint8_t base; } u_level; u_level.real = this->level; *(outbuffer + offset + 0) = (u_level.base >> (8 * 0)) & 0xFF; offset += sizeof(this->level); uint32_t length_name = strlen(this->name); memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); offset += 4; memcpy(outbuffer + offset, this->name, length_name); offset += length_name; uint32_t length_message = strlen(this->message); memcpy(outbuffer + offset, &length_message, sizeof(uint32_t)); offset += 4; memcpy(outbuffer + offset, this->message, length_message); offset += length_message; uint32_t length_hardware_id = strlen(this->hardware_id); memcpy(outbuffer + offset, &length_hardware_id, sizeof(uint32_t)); offset += 4; memcpy(outbuffer + offset, this->hardware_id, length_hardware_id); offset += length_hardware_id; *(outbuffer + offset++) = values_length; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; *(outbuffer + offset++) = 0; for( uint8_t i = 0; i < values_length; i++){ offset += this->values[i].serialize(outbuffer + offset); } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; union { int8_t real; uint8_t base; } u_level; u_level.base = 0; u_level.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); this->level = u_level.real; offset += sizeof(this->level); uint32_t length_name; memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); 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; uint32_t length_message; memcpy(&length_message, (inbuffer + offset), sizeof(uint32_t)); offset += 4; for(unsigned int k= offset; k< offset+length_message; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_message-1]=0; this->message = (char *)(inbuffer + offset-1); offset += length_message; uint32_t length_hardware_id; memcpy(&length_hardware_id, (inbuffer + offset), sizeof(uint32_t)); offset += 4; for(unsigned int k= offset; k< offset+length_hardware_id; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_hardware_id-1]=0; this->hardware_id = (char *)(inbuffer + offset-1); offset += length_hardware_id; uint8_t values_lengthT = *(inbuffer + offset++); if(values_lengthT > values_length) this->values = (diagnostic_msgs::KeyValue*)realloc(this->values, values_lengthT * sizeof(diagnostic_msgs::KeyValue)); offset += 3; values_length = values_lengthT; for( uint8_t i = 0; i < values_length; i++){ offset += this->st_values.deserialize(inbuffer + offset); memcpy( &(this->values[i]), &(this->st_values), sizeof(diagnostic_msgs::KeyValue)); } return offset; } const char * getType(){ return "diagnostic_msgs/DiagnosticStatus"; }; const char * getMD5(){ return "d0ce08bc6e5ba34c7754f563a9cabaf1"; }; }; } #endif