Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <termios.h>
00035 #include <signal.h>
00036 #include <math.h>
00037 #include <stdio.h>
00038 #include <stdlib.h>
00039
00040 #include <ros/ros.h>
00041 #include <geometry_msgs/Twist.h>
00042
00043 #define KEYCODE_A 0x61
00044 #define KEYCODE_D 0x64
00045 #define KEYCODE_S 0x73
00046 #define KEYCODE_W 0x77
00047 #define KEYCODE_Q 0x71
00048 #define KEYCODE_E 0x65
00049
00050 #define KEYCODE_A_CAP 0x41
00051 #define KEYCODE_D_CAP 0x44
00052 #define KEYCODE_S_CAP 0x53
00053 #define KEYCODE_W_CAP 0x57
00054 #define KEYCODE_Q_CAP 0x51
00055 #define KEYCODE_E_CAP 0x45
00056
00057 class TeleopKeyboard
00058 {
00059 private:
00060 double walk_vel, run_vel, yaw_rate, yaw_rate_run;
00061 geometry_msgs::Twist cmd;
00062
00063 ros::NodeHandle n_;
00064 ros::Publisher vel_pub_;
00065
00066 public:
00067 void init()
00068 {
00069 cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00070
00071 vel_pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00072
00073 ros::NodeHandle n_private("~");
00074 n_private.param("walk_vel", walk_vel, 0.5);
00075 n_private.param("run_vel", run_vel, 1.0);
00076 n_private.param("yaw_rate", yaw_rate, 1.0);
00077 n_private.param("yaw_run_rate", yaw_rate_run, 1.5);
00078
00079 }
00080
00081 ~TeleopKeyboard() { }
00082 void keyboardLoop();
00083
00084 };
00085
00086 int kfd = 0;
00087 struct termios cooked, raw;
00088
00089 void quit(int sig)
00090 {
00091 tcsetattr(kfd, TCSANOW, &cooked);
00092 exit(0);
00093 }
00094
00095 int main(int argc, char** argv)
00096 {
00097 ros::init(argc, argv, "teleop_keyboard");
00098
00099 TeleopKeyboard tpk;
00100 tpk.init();
00101
00102 signal(SIGINT,quit);
00103
00104 tpk.keyboardLoop();
00105
00106 return(0);
00107 }
00108
00109 void TeleopKeyboard::keyboardLoop()
00110 {
00111 char c;
00112 bool dirty=false;
00113
00114
00115 tcgetattr(kfd, &cooked);
00116 memcpy(&raw, &cooked, sizeof(struct termios));
00117 raw.c_lflag &=~ (ICANON | ECHO);
00118
00119 raw.c_cc[VEOL] = 1;
00120 raw.c_cc[VEOF] = 2;
00121 tcsetattr(kfd, TCSANOW, &raw);
00122
00123 puts("Reading from keyboard");
00124 puts("---------------------------");
00125 puts("Use 'WASD' to translate");
00126 puts("Use 'QE' to yaw");
00127 puts("Press 'Shift' to run");
00128
00129
00130 for(;;)
00131 {
00132
00133 if(read(kfd, &c, 1) < 0)
00134 {
00135 perror("read():");
00136 exit(-1);
00137 }
00138
00139 cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00140
00141 switch(c)
00142 {
00143
00144 case KEYCODE_W:
00145 cmd.linear.x = walk_vel;
00146 dirty = true;
00147 break;
00148 case KEYCODE_S:
00149 cmd.linear.x = - walk_vel;
00150 dirty = true;
00151 break;
00152 case KEYCODE_A:
00153 cmd.linear.y = walk_vel;
00154 dirty = true;
00155 break;
00156 case KEYCODE_D:
00157 cmd.linear.y = - walk_vel;
00158 dirty = true;
00159 break;
00160 case KEYCODE_Q:
00161 cmd.angular.z = yaw_rate;
00162 dirty = true;
00163 break;
00164 case KEYCODE_E:
00165 cmd.angular.z = - yaw_rate;
00166 dirty = true;
00167 break;
00168
00169
00170 case KEYCODE_W_CAP:
00171 cmd.linear.x = run_vel;
00172 dirty = true;
00173 break;
00174 case KEYCODE_S_CAP:
00175 cmd.linear.x = - run_vel;
00176 dirty = true;
00177 break;
00178 case KEYCODE_A_CAP:
00179 cmd.linear.y = run_vel;
00180 dirty = true;
00181 break;
00182 case KEYCODE_D_CAP:
00183 cmd.linear.y = - run_vel;
00184 dirty = true;
00185 break;
00186 case KEYCODE_Q_CAP:
00187 cmd.angular.z = yaw_rate_run;
00188 dirty = true;
00189 break;
00190 case KEYCODE_E_CAP:
00191 cmd.angular.z = - yaw_rate_run;
00192 dirty = true;
00193 break;
00194 }
00195
00196
00197 if (dirty == true)
00198 {
00199 vel_pub_.publish(cmd);
00200 }
00201
00202
00203 }
00204 }