Revision dd56aeef
ID | dd56aeefcc3c23a50cecd40450abfc1ac8e50f62 |
Added ncurses for key input. It can now publish at a rapid rate because
the key input is non-blocking, and after it exits the terminal is not
screwy, but it's not an ideal solution because ROS_INFO no longer works.
Encapsulated the stuff in nav_lib into a class, MikrokopterControl.
mikrokopter/src/nav_lib.cpp | ||
---|---|---|
1 | 1 |
#include "nav_lib.h" |
2 | 2 |
|
3 | 3 |
|
4 |
void init_control_msg(mikrokopter::Control& req)
|
|
4 |
MikrokopterControl::MikrokopterControl()
|
|
5 | 5 |
{ |
6 |
req.digital[0] = 0;
|
|
7 |
req.digital[1] = 0;
|
|
8 |
req.remoteKey = 0;
|
|
9 |
req.pitch = 0;
|
|
10 |
req.roll = 0;
|
|
11 |
req.yaw = 0;
|
|
12 |
req.thrust = 40;
|
|
13 |
req.height = 0;
|
|
14 |
req.free = 0;
|
|
15 |
req.frame = 7;
|
|
16 |
req.config = 1;
|
|
6 |
control.digital[0] = 0;
|
|
7 |
control.digital[1] = 0;
|
|
8 |
control.remoteKey = 0;
|
|
9 |
control.pitch = 0;
|
|
10 |
control.roll = 0;
|
|
11 |
control.yaw = 0;
|
|
12 |
control.thrust = 40;
|
|
13 |
control.height = 0;
|
|
14 |
control.free = 0;
|
|
15 |
control.frame = 7;
|
|
16 |
control.config = 1;
|
|
17 | 17 |
} |
18 | 18 |
|
19 |
void forward(mikrokopter::Control& req)
|
|
19 |
void MikrokopterControl::forward()
|
|
20 | 20 |
{ |
21 |
req.roll = -15;
|
|
22 |
req.pitch = -15;
|
|
21 |
control.roll = -15;
|
|
22 |
control.pitch = -15;
|
|
23 | 23 |
} |
24 | 24 |
|
25 |
void backward(mikrokopter::Control& req)
|
|
25 |
void MikrokopterControl::backward()
|
|
26 | 26 |
{ |
27 |
req.roll = 15;
|
|
28 |
req.pitch = 15;
|
|
27 |
control.roll = 15;
|
|
28 |
control.pitch = 15;
|
|
29 | 29 |
} |
30 | 30 |
|
31 |
void left(mikrokopter::Control& req)
|
|
31 |
void MikrokopterControl::left()
|
|
32 | 32 |
{ |
33 |
req.roll = -15;
|
|
34 |
req.pitch = 15;
|
|
33 |
control.roll = -15;
|
|
34 |
control.pitch = 15;
|
|
35 | 35 |
} |
36 | 36 |
|
37 |
void right(mikrokopter::Control& req)
|
|
37 |
void MikrokopterControl::right()
|
|
38 | 38 |
{ |
39 |
req.roll = 15;
|
|
40 |
req.pitch = -15;
|
|
39 |
control.roll = 15;
|
|
40 |
control.pitch = -15;
|
|
41 | 41 |
} |
42 | 42 |
|
43 |
void set_thrust(mikrokopter::Control& req, int thrust)
|
|
43 |
void MikrokopterControl::set_thrust(int thrust)
|
|
44 | 44 |
{ |
45 |
req.thrust = thrust; |
|
45 |
control.thrust = thrust; |
|
46 |
} |
|
47 |
|
|
48 |
void MikrokopterControl::publish_on(ros::Publisher& pub) |
|
49 |
{ |
|
50 |
pub.publish(control); |
|
46 | 51 |
} |
47 | 52 |
|
Also available in: Unified diff