keyboard_console_listener.hpp
Go to the documentation of this file.
00001 
00059 #ifndef KEYBOARD_CONSOLE_LISTENER_HPP_
00060 #define KEYBOARD_CONSOLE_LISTENER_HPP_
00061 
00062 #include <stdlib.h>
00063 #include <iostream>
00064 #include <termios.h>
00065 #include <signal.h>
00066 #include <cstring>
00067 
00068 #include <boost/function.hpp>
00069 
00070 namespace cob_3d_mapping_tools
00071 {
00072   class KeyboardConsoleListener
00073   {
00074   public:
00075     struct KEYS
00076     {
00077       enum KeyCode
00078       {
00079         ENTER = 0x0D,
00080         SPACE = 0x20,
00081 
00082         A_CAP = 0x41,
00083         B_CAP, C_CAP, D_CAP, E_CAP, F_CAP, G_CAP, H_CAP, I_CAP, J_CAP, K_CAP, L_CAP, M_CAP, N_CAP,
00084         O_CAP, P_CAP, Q_CAP, R_CAP, S_CAP, T_CAP, U_CAP, V_CAP, W_CAP, X_CAP, Y_CAP, Z_CAP, //=0x5A
00085 
00086         A = 0x61,
00087         B, C, D, E, F, G, H, I, J, K, L, M, N, O, P, Q, R, S, T, U, V, W, X, Y, Z, //=0x7A
00088       };
00089     };
00090 
00091   private:
00092     KeyboardConsoleListener();
00093     // prevent compiler generating methods:
00094     KeyboardConsoleListener(KeyboardConsoleListener const& copy); // Not implemented
00095     KeyboardConsoleListener& operator=(KeyboardConsoleListener const& copy); // Not implemented
00096 
00097   public:
00098     ~KeyboardConsoleListener() { reset(); }
00099 
00100     static KeyboardConsoleListener& get()
00101       {
00102         // The only instance
00103         // Guaranteed to be lazy initialized
00104         // Guaranteed that it will be destroyed correctly
00105         static KeyboardConsoleListener instance;
00106         return instance;
00107       }
00108     static void reset(int sig=0);
00109 
00110     void init(unsigned int timeout=1); // timeout * 0.1 sec [1..255]
00111     char spinOnce();
00112     void spin();
00113     void waitForIt(char c);
00114     char waitForIt(char* c, int size);
00115     bool hasStopped();
00116     void registerKeyboardEventCallback(boost::function<void (char)>& f);
00117 
00118   private:
00119 
00120     struct termios old_conf, new_conf;
00121 
00122     int kfd;
00123     bool tc_modified_;
00124     bool has_stopped_;
00125 
00126     boost::function<void (char)> callback;
00127 
00128   };
00129 
00130 
00131 
00132   /******************************************/
00133   /*************** Definition ***************/
00134   /******************************************/
00135 
00136   KeyboardConsoleListener::KeyboardConsoleListener()
00137     : kfd(0), tc_modified_(false), has_stopped_(true)
00138   { }
00139 
00140   void KeyboardConsoleListener::init(unsigned int timeout)
00141   {
00142     // get the console in raw mode
00143     tcgetattr(kfd, &old_conf);
00144 
00145     new_conf = old_conf;
00146     //memcpy(&raw, &cooked, sizeof(struct termios));
00147     const bool debug_b = false;
00148     if (debug_b)
00149     {
00150       std::cout <<"---Old Config---"<< std::endl;
00151       std::cout <<"ECHO:   "<< ( (new_conf.c_lflag & ECHO) == ECHO ? "True" : "False") << std::endl;
00152       std::cout <<"ECHOE:  "<< ( (new_conf.c_lflag & ECHOE) == ECHOE ? "True" : "False") << std::endl;
00153       std::cout <<"ECHOK:  "<< ( (new_conf.c_lflag & ECHOK) == ECHOK ? "True" : "False") << std::endl;
00154       std::cout <<"ECHONL: "<< ( (new_conf.c_lflag & ECHONL) == ECHONL ? "True" : "False") << std::endl;
00155       std::cout <<"ICANON: "<< ( (new_conf.c_lflag & ICANON) == ICANON ? "True" : "False") << std::endl;
00156       std::cout <<"IEXTEN: "<< ( (new_conf.c_lflag & IEXTEN) == IEXTEN ? "True" : "False") << std::endl;
00157       std::cout <<"ISIG:   "<< ( (new_conf.c_lflag & ISIG) == ISIG ? "True" : "False") << std::endl;
00158       std::cout <<"NOFLSH: "<< ( (new_conf.c_lflag & NOFLSH) == NOFLSH ? "True" : "False") << std::endl;
00159       std::cout <<"TOSTOP: "<< ( (new_conf.c_lflag & TOSTOP) == TOSTOP ? "True" : "False") << std::endl;
00160     }
00161     new_conf.c_lflag &= (~ICANON & ~ECHO);
00162     if (debug_b)
00163     {
00164       std::cout <<"---New Config---"<< std::endl;
00165       std::cout <<"ECHO:   "<< ( (new_conf.c_lflag & ECHO) == ECHO ? "True" : "False") << std::endl;
00166       std::cout <<"ECHOE:  "<< ( (new_conf.c_lflag & ECHOE) == ECHOE ? "True" : "False") << std::endl;
00167       std::cout <<"ECHOK:  "<< ( (new_conf.c_lflag & ECHOK) == ECHOK ? "True" : "False") << std::endl;
00168       std::cout <<"ECHONL: "<< ( (new_conf.c_lflag & ECHONL) == ECHONL ? "True" : "False") << std::endl;
00169       std::cout <<"ICANON: "<< ( (new_conf.c_lflag & ICANON) == ICANON ? "True" : "False") << std::endl;
00170       std::cout <<"IEXTEN: "<< ( (new_conf.c_lflag & IEXTEN) == IEXTEN ? "True" : "False") << std::endl;
00171       std::cout <<"ISIG:   "<< ( (new_conf.c_lflag & ISIG) == ISIG ? "True" : "False") << std::endl;
00172       std::cout <<"NOFLSH: "<< ( (new_conf.c_lflag & NOFLSH) == NOFLSH ? "True" : "False") << std::endl;
00173       std::cout <<"TOSTOP: "<< ( (new_conf.c_lflag & TOSTOP) == TOSTOP ? "True" : "False") << std::endl;
00174     }
00175     // Setting a new line, then end of file
00176     //new_conf.c_lflag = 0;
00177     //new_conf.c_cc[VEOL] = 1;
00178     //new_conf.c_cc[VEOF] = 2;
00179     new_conf.c_cc[VTIME] = std::max(std::min(timeout, (unsigned int)255), (unsigned int)1);
00180     new_conf.c_cc[VMIN] = 0;
00181     tcsetattr(kfd, TCSANOW, &new_conf);
00182     tc_modified_ = true;
00183   }
00184 
00185   char KeyboardConsoleListener::spinOnce()
00186   {
00187     //std::cout << "BF spinOnce"<<std::endl;
00188     char c;
00189     int res=read(kfd, &c, 1);
00190     if(res < 0)
00191     {
00192       std::cerr << "ERR: read():" << std::endl;
00193       KeyboardConsoleListener::reset();
00194     }
00195     else if(res == 0) return NULL;
00196     if (callback) callback(c);
00197     return c;
00198   }
00199 
00200   void KeyboardConsoleListener::spin()
00201   {
00202     has_stopped_=false;
00203     while(!has_stopped_)
00204     {
00205       spinOnce();
00206     }
00207     KeyboardConsoleListener::reset();
00208   }
00209 
00210   void KeyboardConsoleListener::waitForIt(char c)
00211   {
00212     for(;;) { if (spinOnce() == c) return; };
00213   }
00214 
00215   char KeyboardConsoleListener::waitForIt(char* c, int size)
00216   {
00217     //std::cout<<"BF waitForIt"<<std::endl;
00218     for(;;)
00219     {
00220       char c_in = spinOnce();
00221       //std::cout << (int)c_in << std::endl;
00222       for(int i=0; i<size; ++i) { if(c_in == c[i]) { return c_in; } }
00223     }
00224   }
00225 
00226   bool KeyboardConsoleListener::hasStopped()
00227   {
00228     return has_stopped_;
00229   }
00230 
00231   void KeyboardConsoleListener::registerKeyboardEventCallback(boost::function<void (char)>& f)
00232   {
00233     callback = f;
00234   }
00235 
00236   void KeyboardConsoleListener::reset(int sig)
00237   {
00238     if (get().tc_modified_)
00239     {
00240       tcsetattr(get().kfd, TCSANOW, &(get().old_conf));
00241       get().has_stopped_=true;
00242       get().tc_modified_ = false;
00243     }
00244   }
00245 }
00246 
00247 /*
00248   int main(int argc, char** argv)
00249   {
00250   KeyboardConsoleListener::get().init();
00251   KeyboardConsoleListener::get().spin();
00252   return 0;
00253   }
00254 */
00255 #endif //KEYBOARD_CONSOLE_LISTENER_HPP_


cob_3d_mapping_tools
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:27