uos_diffdrive_teleop_key.cpp
Go to the documentation of this file.
1 /*
2  *
3  * Copyright (C) 2015 University of Osnabrück, Germany
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * uos_diffdrive_teleop_key.cpp
20  *
21  * Created on: 16.02.2015
22  * Author: Sebastian Pütz <spuetz@uos.de>
23  */
24 
26 
27 int kfd = 0;
28 struct termios cooked, raw;
29 
31  ros::NodeHandle n_private("~");
32  n_private.param("normal_x", normal_x, 0.5);
33  n_private.param("normal_y", normal_y, 0.5);
34  n_private.param("high_x", high_x, 1.0);
35  n_private.param("high_y", high_y, 1.0);
36 
37  // get the console in raw mode
38  tcgetattr(kfd, &cooked);
39  memcpy(&raw, &cooked, sizeof(struct termios));
40  raw.c_lflag &=~ (ICANON | ECHO);
41  // Setting a new line, then end of file
42  raw.c_cc[VEOL] = 1;
43  raw.c_cc[VEOF] = 2;
44  raw.c_cc[VMIN] = 0;
45  raw.c_cc[VTIME] = 5;
46  tcsetattr(kfd, TCSANOW, &raw);
47 
48  puts("Reading from keyboard");
49  puts("---------------------------");
50  puts("Use 'WS' to translate");
51  puts("Use 'AD' to yaw");
52  puts("Use 'QE' to translate and yaw");
53  puts("Press 'Shift' to run");
54 }
55 
57 {
58  c = 0;
59  // get the next event from
60  // the keyboard
61  if(read(kfd, &c, 1) < 0)
62  {
63  perror("read():");
64  exit(-1);
65  }
66 
67  in.updated = true;
68 
69  switch(c)
70  {
71  // Walking
72  case
73  KEYCODE_W:
75  break;
76  case
77  KEYCODE_S:
78  in.forwards = -normal_y;
79  break;
80  case
81  KEYCODE_A:
82  in.left = normal_x;
83  break;
84  case
85  KEYCODE_D:
86  in.left = -normal_x;
87  break;
88  case
89  KEYCODE_Q:
91  in.left = normal_x;
92  break;
93  case
94  KEYCODE_E:
96  in.left = -normal_x;
97  break;
98 
99  // Running
100  case
102  in.forwards = high_y;
103  break;
104  case
106  in.forwards = -high_y;
107  break;
108  case
110  in.left = high_x;
111  break;
112  case
114  in.left = -high_x;
115  break;
116  case
118  in.forwards = high_y;
119  in.left = high_x;
120  break;
121  case
123  in.forwards = high_y;
124  in.left = -high_x;
125  break;
126  default:
127  in.updated = false;
128  }
129 }
130 
131 void quit(int sig)
132 {
133  tcsetattr(kfd, TCSANOW, &cooked);
134  exit(0);
135 }
136 
137 int main(int argc, char** argv)
138 {
139  ros::init(argc, argv, "uos_diffdrive_teleop_key");
140  TeleopKeyboard teleop;
141  signal(SIGINT,quit);
142  ros::AsyncSpinner spinner(1);
143  spinner.start();
144 
145  while(ros::ok()){
146  teleop.readKeyboard();
147  }
148  return EXIT_SUCCESS;
149 }
#define KEYCODE_S
#define KEYCODE_D
#define KEYCODE_Q_CAP
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void quit(int sig)
#define KEYCODE_E
struct termios cooked raw
#define KEYCODE_A
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
#define KEYCODE_D_CAP
#define KEYCODE_W
#define KEYCODE_W_CAP
#define KEYCODE_S_CAP
#define KEYCODE_Q
#define KEYCODE_A_CAP
#define KEYCODE_E_CAP


uos_diffdrive_teleop
Author(s): Jochen Sprickerhof, Sebastian Pütz
autogenerated on Mon Jun 10 2019 15:49:27