ServoControl.cpp
Go to the documentation of this file.
1 /*
2  * rosserial Servo Control Example
3  *
4  * This sketch demonstrates the control of hobby R/C servos
5  * using ROS and the arduiono
6  *
7  * For the full tutorial write up, visit
8  * www.ros.org/wiki/rosserial_mbed_demos
9  *
10  */
11 
12 #include "mbed.h"
13 #include "Servo.h"
14 #include <ros.h>
15 #include <std_msgs/UInt16.h>
16 
18 
19 #ifdef TARGET_LPC1768
20 Servo servo(p21);
21 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
22 Servo servo(D8);
23 #else
24 #error "You need to specify a pin for the Servo"
25 #endif
26 DigitalOut myled(LED1);
27 
28 void servo_cb( const std_msgs::UInt16& cmd_msg) {
29  servo.position(cmd_msg.data); //set servo angle, should be from 0-180
30  myled = !myled; //toggle led
31 }
32 
33 
35 
36 int main() {
37 
38  nh.initNode();
39  nh.subscribe(sub);
40 
41  while (1) {
42  nh.spinOnce();
43  wait_ms(1);
44  }
45 }
46 
void servo_cb(const std_msgs::UInt16 &cmd_msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber< std_msgs::UInt16 > sub("servo", servo_cb)
ros::NodeHandle nh
int main()
DigitalOut myled(LED1)
Definition: Servo.h:52


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48