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/keyboard_control.cpp | ||
---|---|---|
10 | 10 |
#include <signal.h> |
11 | 11 |
#include <termios.h> |
12 | 12 |
#include <stdio.h> |
13 |
#include <ncurses.h> |
|
13 | 14 |
|
14 | 15 |
#include "nav_lib.h" |
15 | 16 |
|
... | ... | |
19 | 20 |
#define KEYCODE_D 0x42 |
20 | 21 |
#define KEYCODE_Q 0x71 |
21 | 22 |
|
22 |
// Keyboard control variables |
|
23 |
int kfd = 0; |
|
24 |
struct termios cooked, raw; |
|
25 |
|
|
26 | 23 |
class KeyboardControl |
27 | 24 |
{ |
28 | 25 |
public: |
... | ... | |
37 | 34 |
{ |
38 | 35 |
} |
39 | 36 |
|
40 |
void quit(int sig) |
|
41 |
{ |
|
42 |
tcsetattr(kfd, TCSANOW, &cooked); |
|
43 |
ros::shutdown(); |
|
44 |
exit(0); |
|
45 |
} |
|
46 |
|
|
47 | 37 |
void KeyboardControl::keyLoop() |
48 | 38 |
{ |
49 | 39 |
|
50 | 40 |
ros::NodeHandle n; |
51 | 41 |
ros::Publisher pub = n.advertise<mikrokopter::Control>("/mikrokopter/req_set_control", 100); |
52 | 42 |
|
53 |
mikrokopter::Control req;
|
|
43 |
MikrokopterControl control;
|
|
54 | 44 |
|
55 | 45 |
ros::Rate loop_rate(25); |
56 | 46 |
|
57 | 47 |
char c; |
58 |
bool dirty=false; |
|
59 | 48 |
|
60 | 49 |
// 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); |
|
50 |
initscr(); |
|
51 |
timeout(0); |
|
52 |
noecho(); |
|
53 |
cbreak(); |
|
69 | 54 |
|
70 | 55 |
puts("Reading from keyboard"); |
71 | 56 |
puts("---------------------------"); |
72 | 57 |
puts("Use arrow keys to command the quadrotor."); |
73 | 58 |
|
74 |
while(true)
|
|
59 |
while(ros::ok())
|
|
75 | 60 |
{ |
76 | 61 |
// get the next event from the keyboard |
77 |
if(read(kfd, &c, 1) < 0) |
|
78 |
{ |
|
79 |
perror("read():"); |
|
80 |
exit(-1); |
|
81 |
} |
|
62 |
c = getch(); |
|
82 | 63 |
|
83 | 64 |
//ROS_INFO("key press: 0x%02X\n", c); |
84 | 65 |
//ROS_INFO("key press: %c\n", c); |
... | ... | |
88 | 69 |
case KEYCODE_L: |
89 | 70 |
case 'a': |
90 | 71 |
ROS_INFO("A"); |
91 |
left(req); |
|
92 |
dirty = true; |
|
72 |
control.left(); |
|
93 | 73 |
break; |
94 | 74 |
case KEYCODE_R: |
95 | 75 |
case 'd': |
96 | 76 |
ROS_INFO("D"); |
97 |
right(req); |
|
98 |
dirty = true; |
|
77 |
control.right(); |
|
99 | 78 |
break; |
100 | 79 |
case KEYCODE_U: |
101 | 80 |
case 'w': |
102 | 81 |
ROS_INFO("W"); |
103 |
forward(req); |
|
104 |
dirty = true; |
|
82 |
control.forward(); |
|
105 | 83 |
break; |
106 | 84 |
case KEYCODE_D: |
107 | 85 |
case 's': |
108 | 86 |
ROS_INFO("B"); |
109 |
backward(req); |
|
110 |
dirty = true; |
|
87 |
control.backward(); |
|
111 | 88 |
break; |
112 | 89 |
case 'r': |
113 | 90 |
ROS_INFO("UP"); |
... | ... | |
119 | 96 |
break; |
120 | 97 |
} |
121 | 98 |
|
122 |
if(dirty) |
|
123 |
{ |
|
124 |
pub.publish(req); |
|
125 |
ros::spinOnce(); |
|
126 |
dirty=false; |
|
127 |
} |
|
99 |
control.publish_on(pub); |
|
100 |
ros::spinOnce(); |
|
101 |
loop_rate.sleep(); |
|
128 | 102 |
} |
129 |
|
|
103 |
|
|
104 |
endwin(); |
|
130 | 105 |
return; |
131 | 106 |
} |
132 | 107 |
|
... | ... | |
135 | 110 |
ros::init(argc, argv, "keyboard_control"); |
136 | 111 |
KeyboardControl teleop_turtle; |
137 | 112 |
|
138 |
signal(SIGINT,quit); |
|
139 |
|
|
140 | 113 |
// This commands loops infinitely |
141 | 114 |
teleop_turtle.keyLoop(); |
142 | 115 |
|
Also available in: Unified diff