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 
00049 #define KEYCODE_A_CAP 0x41
00050 #define KEYCODE_D_CAP 0x44
00051 #define KEYCODE_S_CAP 0x53
00052 #define KEYCODE_W_CAP 0x57
00053 #define KEYCODE_Q_CAP 0x51
00054 #define KEYCODE_E_CAP 0x45
00055 
00056 class TeleopPR2Keyboard
00057 {
00058   private:
00059   double walk_vel, run_vel, yaw_rate, yaw_rate_run;
00060   geometry_msgs::Twist cmd;
00061 
00062   ros::NodeHandle n_;
00063   ros::Publisher vel_pub_;
00064 
00065   public:
00066   void init()
00067   { 
00068     cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00069 
00070     vel_pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00071 
00072     ros::NodeHandle n_private("~");
00073     n_private.param("walk_vel", walk_vel, 0.5);
00074     n_private.param("run_vel", run_vel, 1.0);
00075     n_private.param("yaw_rate", yaw_rate, 1.0);
00076     n_private.param("yaw_run_rate", yaw_rate_run, 1.5);
00077 
00078   }
00079   
00080   ~TeleopPR2Keyboard()   { }
00081   void keyboardLoop();
00082 
00083 };
00084 
00085 int kfd = 0;
00086 struct termios cooked, raw;
00087 
00088 void quit(int sig)
00089 {
00090   tcsetattr(kfd, TCSANOW, &cooked);
00091   exit(0);
00092 }
00093 
00094 int main(int argc, char** argv)
00095 {
00096   ros::init(argc, argv, "pr2_base_keyboard");
00097 
00098   TeleopPR2Keyboard tpk;
00099   tpk.init();
00100 
00101   signal(SIGINT,quit);
00102 
00103   tpk.keyboardLoop();
00104 
00105   return(0);
00106 }
00107 
00108 void TeleopPR2Keyboard::keyboardLoop()
00109 {
00110   char c;
00111   bool dirty=false;
00112 
00113   
00114   tcgetattr(kfd, &cooked);
00115   memcpy(&raw, &cooked, sizeof(struct termios));
00116   raw.c_lflag &=~ (ICANON | ECHO);
00117   
00118   raw.c_cc[VEOL] = 1;
00119   raw.c_cc[VEOF] = 2;
00120   tcsetattr(kfd, TCSANOW, &raw);
00121 
00122   puts("Reading from keyboard");
00123   puts("---------------------------");
00124   puts("Use 'WASD' to translate");
00125   puts("Use 'QE' to yaw");
00126   puts("Press 'Shift' to run");
00127 
00128 
00129   for(;;)
00130   {
00131     
00132     if(read(kfd, &c, 1) < 0)
00133     {
00134       perror("read():");
00135       exit(-1);
00136     }
00137 
00138     cmd.linear.x = cmd.linear.y = cmd.angular.z = 0;
00139 
00140     switch(c)
00141     {
00142       
00143     case KEYCODE_W:
00144       cmd.linear.x = walk_vel;
00145       dirty = true;
00146       break;
00147     case KEYCODE_S:
00148       cmd.linear.x = - walk_vel;
00149       dirty = true;
00150       break;
00151     case KEYCODE_A:
00152       cmd.linear.y = walk_vel;
00153       dirty = true;
00154       break;
00155     case KEYCODE_D:
00156       cmd.linear.y = - walk_vel;
00157       dirty = true;
00158       break;
00159     case KEYCODE_Q:
00160       cmd.angular.z = yaw_rate;
00161       dirty = true;
00162       break;
00163     case KEYCODE_E:
00164       cmd.angular.z = - yaw_rate;
00165       dirty = true;
00166       break;
00167 
00168       
00169     case KEYCODE_W_CAP:
00170       cmd.linear.x = run_vel;
00171       dirty = true;
00172       break;
00173     case KEYCODE_S_CAP:
00174       cmd.linear.x = - run_vel;
00175       dirty = true;
00176       break;
00177     case KEYCODE_A_CAP:
00178       cmd.linear.y = run_vel;
00179       dirty = true;
00180       break;
00181     case KEYCODE_D_CAP:
00182       cmd.linear.y = - run_vel;
00183       dirty = true;
00184       break;
00185     case KEYCODE_Q_CAP:
00186       cmd.angular.z = yaw_rate_run;
00187       dirty = true;
00188       break;
00189     case KEYCODE_E_CAP:
00190       cmd.angular.z = - yaw_rate_run;
00191       dirty = true;
00192       break;
00193     }
00194 
00195     
00196     if (dirty == true)
00197     {
00198       vel_pub_.publish(cmd);
00199     }
00200 
00201 
00202   }
00203 }