#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <stdio.h>
#include <unistd.h>
#include <termios.h>
#include <map>
Go to the source code of this file.
|
int | getch (void) |
|
char | key (' ') |
|
int | main (int argc, char **argv) |
|
float | speed (0.5) |
|
float | th (0) |
|
float | turn (1.0) |
|
float | x (0) |
|
float | y (0) |
|
float | z (0) |
|
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
std::map<char, std::vector<float> > moveBindings |
Initial value:{
{'i', {1, 0, 0, 0}},
{'o', {1, 0, 0, -1}},
{'j', {0, 0, 0, 1}},
{'l', {0, 0, 0, -1}},
{'u', {1, 0, 0, 1}},
{',', {-1, 0, 0, 0}},
{'.', {-1, 0, 0, 1}},
{'m', {-1, 0, 0, -1}},
{'O', {1, -1, 0, 0}},
{'I', {1, 0, 0, 0}},
{'J', {0, 1, 0, 0}},
{'L', {0, -1, 0, 0}},
{'U', {1, 1, 0, 0}},
{'<', {-1, 0, 0, 0}},
{'>', {-1, -1, 0, 0}},
{'M', {-1, 1, 0, 0}},
{'t', {0, 0, 1, 0}},
{'b', {0, 0, -1, 0}},
{'k', {0, 0, 0, 0}},
{'K', {0, 0, 0, 0}}
}
Definition at line 12 of file teleop_twist_keyboard.cpp.
Initial value:= R"(
Reading from the keyboard and Publishing to Twist!
---------------------------
Moving around:
u i o
j k l
m , .
For Holonomic mode (strafing), hold down the shift key:
---------------------------
U I O
J K L
M < >
t : up (+z)
b : down (-z)
anything else : stop
q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%
CTRL-C to quit
)"
Definition at line 47 of file teleop_twist_keyboard.cpp.
std::map<char, std::vector<float> > speedBindings |
Initial value:{
{'q', {1.1, 1.1}},
{'z', {0.9, 0.9}},
{'w', {1.1, 1}},
{'x', {0.9, 1}},
{'e', {1, 1.1}},
{'c', {1, 0.9}}
}
Definition at line 37 of file teleop_twist_keyboard.cpp.