This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ServoControl.cpp Source File

ServoControl.cpp

00001 //#define COMPILE_SERVOCONTROL_CODE_ROSSERIAL
00002 #ifdef  COMPILE_SERVOCONTROL_CODE_ROSSERIAL
00003 
00004 /*
00005  * rosserial Servo Control Example
00006  *
00007  * This sketch demonstrates the control of hobby R/C servos
00008  * using ROS and the arduiono
00009  *
00010  * For the full tutorial write up, visit
00011  * www.ros.org/wiki/rosserial_arduino_demos
00012  *
00013  * For more information on the Arduino Servo Library
00014  * Checkout :
00015  * http://www.arduino.cc/en/Reference/Servo
00016  */
00017 
00018 #include "mbed.h"
00019 #include "Servo.h"
00020 #include <ros.h>
00021 #include <std_msgs/UInt16.h>
00022 
00023 ros::NodeHandle  nh;
00024 
00025 Servo servo(p21);
00026 DigitalOut myled(LED1);
00027 
00028 void servo_cb( const std_msgs::UInt16& cmd_msg) {
00029     servo.position(cmd_msg.data); //set servo angle, should be from 0-180
00030     myled = !myled;  //toggle led
00031 }
00032 
00033 
00034 ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
00035 
00036 int main() {
00037 
00038     nh.initNode();
00039     nh.subscribe(sub);
00040 
00041     while (1) {
00042         nh.spinOnce();
00043         wait_ms(1);
00044     }
00045 }
00046 #endif