root / mikrokopter / src / keyboard_control.cpp @ 493cca7c
History | View | Annotate | Download (2.92 KB)
1 |
/**
|
---|---|
2 |
* @brief A node responsible for keyboard commands which will be sent to
|
3 |
* the MikroKopter
|
4 |
*
|
5 |
* @author CMU Quadrotor Project
|
6 |
* @author Alex Zirbel
|
7 |
*/
|
8 |
|
9 |
#include <ros/ros.h> |
10 |
#include <signal.h> |
11 |
#include <termios.h> |
12 |
#include <stdio.h> |
13 |
|
14 |
#include "nav_lib.h" |
15 |
|
16 |
#define KEYCODE_R 0x43 |
17 |
#define KEYCODE_L 0x44 |
18 |
#define KEYCODE_U 0x41 |
19 |
#define KEYCODE_D 0x42 |
20 |
#define KEYCODE_Q 0x71 |
21 |
|
22 |
// Keyboard control variables
|
23 |
int kfd = 0; |
24 |
struct termios cooked, raw;
|
25 |
|
26 |
class KeyboardControl |
27 |
{ |
28 |
public:
|
29 |
KeyboardControl(); |
30 |
void keyLoop();
|
31 |
|
32 |
private:
|
33 |
ros::NodeHandle n; |
34 |
}; |
35 |
|
36 |
KeyboardControl::KeyboardControl() |
37 |
{ |
38 |
} |
39 |
|
40 |
void quit(int sig) |
41 |
{ |
42 |
tcsetattr(kfd, TCSANOW, &cooked); |
43 |
ros::shutdown(); |
44 |
exit(0);
|
45 |
} |
46 |
|
47 |
void KeyboardControl::keyLoop()
|
48 |
{ |
49 |
|
50 |
ros::NodeHandle n; |
51 |
ros::Publisher pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100); |
52 |
|
53 |
mikrokopter::Control req; |
54 |
|
55 |
ros::Rate loop_rate(25);
|
56 |
|
57 |
char c;
|
58 |
bool dirty=false; |
59 |
|
60 |
// get the console in raw mode
|
61 |
tcgetattr(kfd, &cooked); |
62 |
memcpy(&raw, &cooked, sizeof(struct termios)); |
63 |
raw.c_lflag &=~ (ICANON | ECHO); |
64 |
|
65 |
// Setting a new line, then end of file
|
66 |
raw.c_cc[VEOL] = 1;
|
67 |
raw.c_cc[VEOF] = 2;
|
68 |
tcsetattr(kfd, TCSANOW, &raw); |
69 |
|
70 |
puts("Reading from keyboard");
|
71 |
puts("---------------------------");
|
72 |
puts("Use arrow keys to command the quadrotor.");
|
73 |
|
74 |
while(true) |
75 |
{ |
76 |
// get the next event from the keyboard
|
77 |
if(read(kfd, &c, 1) < 0) |
78 |
{ |
79 |
perror("read():");
|
80 |
exit(-1);
|
81 |
} |
82 |
|
83 |
//ROS_INFO("key press: 0x%02X\n", c);
|
84 |
//ROS_INFO("key press: %c\n", c);
|
85 |
|
86 |
switch(c)
|
87 |
{ |
88 |
case KEYCODE_L:
|
89 |
case 'a': |
90 |
ROS_INFO("A");
|
91 |
left(req); |
92 |
dirty = true;
|
93 |
break;
|
94 |
case KEYCODE_R:
|
95 |
case 'd': |
96 |
ROS_INFO("D");
|
97 |
right(req); |
98 |
dirty = true;
|
99 |
break;
|
100 |
case KEYCODE_U:
|
101 |
case 'w': |
102 |
ROS_INFO("W");
|
103 |
forward(req); |
104 |
dirty = true;
|
105 |
break;
|
106 |
case KEYCODE_D:
|
107 |
case 's': |
108 |
ROS_INFO("B");
|
109 |
backward(req); |
110 |
dirty = true;
|
111 |
break;
|
112 |
case 'r': |
113 |
ROS_INFO("UP");
|
114 |
//set_throttle(&pub, );
|
115 |
break;
|
116 |
case 'f': |
117 |
ROS_INFO("DOWN");
|
118 |
//set_throttle(&pub);
|
119 |
break;
|
120 |
} |
121 |
|
122 |
if(dirty)
|
123 |
{ |
124 |
pub.publish(req); |
125 |
ros::spinOnce(); |
126 |
dirty=false;
|
127 |
} |
128 |
} |
129 |
|
130 |
return;
|
131 |
} |
132 |
|
133 |
int main(int argc, char** argv) |
134 |
{ |
135 |
ros::init(argc, argv, "keyboard_control");
|
136 |
KeyboardControl teleop_turtle; |
137 |
|
138 |
signal(SIGINT,quit); |
139 |
|
140 |
// This commands loops infinitely
|
141 |
teleop_turtle.keyLoop(); |
142 |
|
143 |
return(0); |
144 |
} |
145 |
|
146 |
|