ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged

Dependencies:   rosserial_hydro

Library and program still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:54:04 2015 +0000
Revision:
0:cb1dffdc7d05
Error: ; "mbed::Stream::Stream(const mbed::Stream &)" (declared at <a href="#" onmousedown="mbed_doc_goto('/mbed_roshydro_test//extras/mbed_e188a91d3eaa/Stream.h', '59'); return false;">/extras/mbed_e188a91d3eaa/Stream.h:59</a>) is inaccessible in "ext

Who changed what in which revision?

UserRevisionLine numberNew contents of line
akashvibhute 0:cb1dffdc7d05 1 //#define COMPILE_SERVOCONTROL_CODE_ROSSERIAL
akashvibhute 0:cb1dffdc7d05 2 #ifdef COMPILE_SERVOCONTROL_CODE_ROSSERIAL
akashvibhute 0:cb1dffdc7d05 3
akashvibhute 0:cb1dffdc7d05 4 /*
akashvibhute 0:cb1dffdc7d05 5 * rosserial Servo Control Example
akashvibhute 0:cb1dffdc7d05 6 *
akashvibhute 0:cb1dffdc7d05 7 * This sketch demonstrates the control of hobby R/C servos
akashvibhute 0:cb1dffdc7d05 8 * using ROS and the arduiono
akashvibhute 0:cb1dffdc7d05 9 *
akashvibhute 0:cb1dffdc7d05 10 * For the full tutorial write up, visit
akashvibhute 0:cb1dffdc7d05 11 * www.ros.org/wiki/rosserial_arduino_demos
akashvibhute 0:cb1dffdc7d05 12 *
akashvibhute 0:cb1dffdc7d05 13 * For more information on the Arduino Servo Library
akashvibhute 0:cb1dffdc7d05 14 * Checkout :
akashvibhute 0:cb1dffdc7d05 15 * http://www.arduino.cc/en/Reference/Servo
akashvibhute 0:cb1dffdc7d05 16 */
akashvibhute 0:cb1dffdc7d05 17
akashvibhute 0:cb1dffdc7d05 18 #include "mbed.h"
akashvibhute 0:cb1dffdc7d05 19 #include "Servo.h"
akashvibhute 0:cb1dffdc7d05 20 #include <ros.h>
akashvibhute 0:cb1dffdc7d05 21 #include <std_msgs/UInt16.h>
akashvibhute 0:cb1dffdc7d05 22
akashvibhute 0:cb1dffdc7d05 23 ros::NodeHandle nh;
akashvibhute 0:cb1dffdc7d05 24
akashvibhute 0:cb1dffdc7d05 25 Servo servo(p21);
akashvibhute 0:cb1dffdc7d05 26 DigitalOut myled(LED1);
akashvibhute 0:cb1dffdc7d05 27
akashvibhute 0:cb1dffdc7d05 28 void servo_cb( const std_msgs::UInt16& cmd_msg) {
akashvibhute 0:cb1dffdc7d05 29 servo.position(cmd_msg.data); //set servo angle, should be from 0-180
akashvibhute 0:cb1dffdc7d05 30 myled = !myled; //toggle led
akashvibhute 0:cb1dffdc7d05 31 }
akashvibhute 0:cb1dffdc7d05 32
akashvibhute 0:cb1dffdc7d05 33
akashvibhute 0:cb1dffdc7d05 34 ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
akashvibhute 0:cb1dffdc7d05 35
akashvibhute 0:cb1dffdc7d05 36 int main() {
akashvibhute 0:cb1dffdc7d05 37
akashvibhute 0:cb1dffdc7d05 38 nh.initNode();
akashvibhute 0:cb1dffdc7d05 39 nh.subscribe(sub);
akashvibhute 0:cb1dffdc7d05 40
akashvibhute 0:cb1dffdc7d05 41 while (1) {
akashvibhute 0:cb1dffdc7d05 42 nh.spinOnce();
akashvibhute 0:cb1dffdc7d05 43 wait_ms(1);
akashvibhute 0:cb1dffdc7d05 44 }
akashvibhute 0:cb1dffdc7d05 45 }
akashvibhute 0:cb1dffdc7d05 46 #endif