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 #include <termios.h>
00034 #include <signal.h>
00035 #include <math.h>
00036 #include <stdio.h>
00037 #include <stdlib.h>
00038
00039 #include <ros/ros.h>
00040 #include <geometry_msgs/Twist.h>
00041
00042 #define KEYCODE_A 0x61
00043 #define KEYCODE_D 0x64
00044 #define KEYCODE_S 0x73
00045 #define KEYCODE_W 0x77
00046 #define KEYCODE_Q 0x71
00047 #define KEYCODE_E 0x65
00048 #define KEYCODE_X 0x78
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 TeleopNaoKeyboard
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 ~TeleopNaoKeyboard() { }
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, "nao_base_keyboard");
00098
00099 TeleopNaoKeyboard tpk;
00100 tpk.init();
00101
00102 signal(SIGINT,quit);
00103
00104 tpk.keyboardLoop();
00105
00106 return(0);
00107 }
00108
00109 void TeleopNaoKeyboard::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("Use 'X' to stop");
00128 puts("Press 'Shift' to run");
00129
00130
00131 for(;;)
00132 {
00133
00134 if(read(kfd, &c, 1) < 0)
00135 {
00136 perror("read():");
00137 exit(-1);
00138 }
00139
00140 cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00141
00142 switch(c)
00143 {
00144
00145 case KEYCODE_W:
00146 cmd.linear.x = walk_vel;
00147 dirty = true;
00148 break;
00149 case KEYCODE_S:
00150 cmd.linear.x = - walk_vel;
00151 dirty = true;
00152 break;
00153 case KEYCODE_A:
00154 cmd.linear.y = walk_vel;
00155 dirty = true;
00156 break;
00157 case KEYCODE_D:
00158 cmd.linear.y = - walk_vel;
00159 dirty = true;
00160 break;
00161 case KEYCODE_Q:
00162 cmd.angular.z = yaw_rate;
00163 dirty = true;
00164 break;
00165 case KEYCODE_E:
00166 cmd.angular.z = - yaw_rate;
00167 dirty = true;
00168 break;
00169
00170 case KEYCODE_X:
00171 cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00172 dirty = true;
00173 break;
00174
00175
00176 case KEYCODE_W_CAP:
00177 cmd.linear.x = run_vel;
00178 dirty = true;
00179 break;
00180 case KEYCODE_S_CAP:
00181 cmd.linear.x = - run_vel;
00182 dirty = true;
00183 break;
00184 case KEYCODE_A_CAP:
00185 cmd.linear.y = run_vel;
00186 dirty = true;
00187 break;
00188 case KEYCODE_D_CAP:
00189 cmd.linear.y = - run_vel;
00190 dirty = true;
00191 break;
00192 case KEYCODE_Q_CAP:
00193 cmd.angular.z = yaw_rate_run;
00194 dirty = true;
00195 break;
00196 case KEYCODE_E_CAP:
00197 cmd.angular.z = - yaw_rate_run;
00198 dirty = true;
00199 break;
00200 }
00201
00202 if (dirty == true)
00203 {
00204 vel_pub_.publish(cmd);
00205 }
00206
00207
00208 }
00209 }