Revision d58012b5
ID | d58012b5c30fd42d945aed8a30192ec5b4dcd9dc |
fixing forwards/backwards, adding level function
mikrokopter/src/keyboard_control.cpp | ||
---|---|---|
86 | 86 |
ROS_INFO("B"); |
87 | 87 |
control.backward(); |
88 | 88 |
break; |
89 |
case ' ': |
|
90 |
ROS_INFO("space"); |
|
91 |
control.level(); |
|
92 |
break; |
|
89 | 93 |
case 'r': |
90 | 94 |
ROS_INFO("UP"); |
91 | 95 |
//set_throttle(&pub, ); |
mikrokopter/src/nav_lib.cpp | ||
---|---|---|
18 | 18 |
|
19 | 19 |
void MikrokopterControl::forward() |
20 | 20 |
{ |
21 |
control.roll = 15; |
|
22 |
control.pitch = 15; |
|
23 |
} |
|
24 |
|
|
25 |
void MikrokopterControl::backward() |
|
26 |
{ |
|
21 | 27 |
control.roll = -15; |
22 | 28 |
control.pitch = -15; |
23 | 29 |
} |
24 | 30 |
|
25 |
void MikrokopterControl::backward()
|
|
31 |
void MikrokopterControl::left()
|
|
26 | 32 |
{ |
27 | 33 |
control.roll = 15; |
28 |
control.pitch = 15; |
|
34 |
control.pitch = -15;
|
|
29 | 35 |
} |
30 | 36 |
|
31 |
void MikrokopterControl::left()
|
|
37 |
void MikrokopterControl::right()
|
|
32 | 38 |
{ |
33 | 39 |
control.roll = -15; |
34 | 40 |
control.pitch = 15; |
35 | 41 |
} |
36 | 42 |
|
37 |
void MikrokopterControl::right()
|
|
43 |
void MikrokopterControl::level()
|
|
38 | 44 |
{ |
39 |
control.roll = 15;
|
|
40 |
control.pitch = -15;
|
|
45 |
control.roll = 0;
|
|
46 |
control.pitch = 0;
|
|
41 | 47 |
} |
42 | 48 |
|
43 | 49 |
void MikrokopterControl::set_thrust(int thrust) |
mikrokopter/src/nav_lib.h | ||
---|---|---|
8 | 8 |
void backward(); |
9 | 9 |
void left(); |
10 | 10 |
void right(); |
11 |
void level(); |
|
11 | 12 |
void set_thrust(int thrust); |
12 | 13 |
void publish_on(ros::Publisher& pub); |
13 | 14 |
private: |
Also available in: Unified diff