src
examples
ServoControl
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
17
ros::NodeHandle
nh
;
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
34
ros::Subscriber<std_msgs::UInt16>
sub
(
"servo"
,
servo_cb
);
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
myled
DigitalOut myled(LED1)
nh
ros::NodeHandle nh
Definition:
ServoControl.cpp:17
Servo.h
Servo
Definition:
Servo.h:52
main
int main()
Definition:
ServoControl.cpp:36
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
sub
ros::Subscriber< std_msgs::UInt16 > sub("servo", servo_cb)
servo_cb
void servo_cb(const std_msgs::UInt16 &cmd_msg)
Definition:
ServoControl.cpp:28
ros::Subscriber
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08