ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.
Dependents: rosserial_mbed_hello_world_publisher_kinetic s-rov-firmware ROS_HCSR04 DISCO-F469NI_LCDTS_demo ... more
ROSSerial_mbed for Kinetic 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_kinetic
rosserial_mbed Hello World example for Kinetic Kame 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(); } }
rosgraph_msgs/Log.h
- Committer:
- garyservin
- Date:
- 2016-12-31
- Revision:
- 0:9e9b7db60fd5
File content as of revision 0:9e9b7db60fd5:
#ifndef _ROS_rosgraph_msgs_Log_h #define _ROS_rosgraph_msgs_Log_h #include <stdint.h> #include <string.h> #include <stdlib.h> #include "ros/msg.h" #include "std_msgs/Header.h" namespace rosgraph_msgs { class Log : public ros::Msg { public: typedef std_msgs::Header _header_type; _header_type header; typedef int8_t _level_type; _level_type level; typedef const char* _name_type; _name_type name; typedef const char* _msg_type; _msg_type msg; typedef const char* _file_type; _file_type file; typedef const char* _function_type; _function_type function; typedef uint32_t _line_type; _line_type line; uint32_t topics_length; typedef char* _topics_type; _topics_type st_topics; _topics_type * topics; enum { DEBUG = 1 }; enum { INFO = 2 }; enum { WARN = 4 }; enum { ERROR = 8 }; enum { FATAL = 16 }; Log(): header(), level(0), name(""), msg(""), file(""), function(""), line(0), topics_length(0), topics(NULL) { } virtual int serialize(unsigned char *outbuffer) const { int offset = 0; offset += this->header.serialize(outbuffer + offset); 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); varToArr(outbuffer + offset, length_name); offset += 4; memcpy(outbuffer + offset, this->name, length_name); offset += length_name; uint32_t length_msg = strlen(this->msg); varToArr(outbuffer + offset, length_msg); offset += 4; memcpy(outbuffer + offset, this->msg, length_msg); offset += length_msg; uint32_t length_file = strlen(this->file); varToArr(outbuffer + offset, length_file); offset += 4; memcpy(outbuffer + offset, this->file, length_file); offset += length_file; uint32_t length_function = strlen(this->function); varToArr(outbuffer + offset, length_function); offset += 4; memcpy(outbuffer + offset, this->function, length_function); offset += length_function; *(outbuffer + offset + 0) = (this->line >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (this->line >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (this->line >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (this->line >> (8 * 3)) & 0xFF; offset += sizeof(this->line); *(outbuffer + offset + 0) = (this->topics_length >> (8 * 0)) & 0xFF; *(outbuffer + offset + 1) = (this->topics_length >> (8 * 1)) & 0xFF; *(outbuffer + offset + 2) = (this->topics_length >> (8 * 2)) & 0xFF; *(outbuffer + offset + 3) = (this->topics_length >> (8 * 3)) & 0xFF; offset += sizeof(this->topics_length); for( uint32_t i = 0; i < topics_length; i++){ uint32_t length_topicsi = strlen(this->topics[i]); varToArr(outbuffer + offset, length_topicsi); offset += 4; memcpy(outbuffer + offset, this->topics[i], length_topicsi); offset += length_topicsi; } return offset; } virtual int deserialize(unsigned char *inbuffer) { int offset = 0; offset += this->header.deserialize(inbuffer + offset); 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; 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; uint32_t length_msg; arrToVar(length_msg, (inbuffer + offset)); offset += 4; for(unsigned int k= offset; k< offset+length_msg; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_msg-1]=0; this->msg = (char *)(inbuffer + offset-1); offset += length_msg; uint32_t length_file; arrToVar(length_file, (inbuffer + offset)); offset += 4; for(unsigned int k= offset; k< offset+length_file; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_file-1]=0; this->file = (char *)(inbuffer + offset-1); offset += length_file; uint32_t length_function; arrToVar(length_function, (inbuffer + offset)); offset += 4; for(unsigned int k= offset; k< offset+length_function; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_function-1]=0; this->function = (char *)(inbuffer + offset-1); offset += length_function; this->line = ((uint32_t) (*(inbuffer + offset))); this->line |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); this->line |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); this->line |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->line); uint32_t topics_lengthT = ((uint32_t) (*(inbuffer + offset))); topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); topics_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); offset += sizeof(this->topics_length); if(topics_lengthT > topics_length) this->topics = (char**)realloc(this->topics, topics_lengthT * sizeof(char*)); topics_length = topics_lengthT; for( uint32_t i = 0; i < topics_length; i++){ uint32_t length_st_topics; arrToVar(length_st_topics, (inbuffer + offset)); offset += 4; for(unsigned int k= offset; k< offset+length_st_topics; ++k){ inbuffer[k-1]=inbuffer[k]; } inbuffer[offset+length_st_topics-1]=0; this->st_topics = (char *)(inbuffer + offset-1); offset += length_st_topics; memcpy( &(this->topics[i]), &(this->st_topics), sizeof(char*)); } return offset; } const char * getType(){ return "rosgraph_msgs/Log"; }; const char * getMD5(){ return "acffd30cd6b6de30f120938c17c593fb"; }; }; } #endif