teleop_arm_key.h
Go to the documentation of this file.
00001 /*
00002  * teleop_arm_key.h
00003  * Copyright 2013 University of Massachusetts Lowell
00004  * Author: Jonathan Hasenzahl
00005  */
00006 
00007 #ifndef TELEOP_ARM_KEY_H_
00008 #define TELEOP_ARM_KEY_H_
00009 
00010 #include "ros/ros.h"
00011 #include "arm/constant_move.h"
00012 
00013 // Arm control key codes
00014 #define KEYCODE_W         0x77 // ARM_FORWARD
00015 #define KEYCODE_A         0x61 // ARM_LEFT
00016 #define KEYCODE_S         0x73 // ARM_BACKWARD
00017 #define KEYCODE_D         0x64 // ARM_RIGHT
00018 #define KEYCODE_Z         0x7A // ARM_UP
00019 #define KEYCODE_X         0x78 // ARM_DOWN
00020 #define KEYCODE_F         0x66 // FOLD
00021 #define KEYCODE_U         0x75 // UNFOLD
00022 
00023 // Claw control key codes
00024 #define KEYCODE_NUM_4     0x34 // CLAW_YAW_LEFT
00025 #define KEYCODE_NUM_6     0x36 // CLAW_YAW_RIGHT
00026 #define KEYCODE_NUM_8     0x38 // CLAW_PITCH_UP
00027 #define KEYCODE_NUM_2     0x32 // CLAW_PITCH_DOWN
00028 #define KEYCODE_NUM_7     0x37 // CLAW_ROLL_LEFT
00029 #define KEYCODE_NUM_9     0x39 // CLAW_ROLL_RIGHT
00030 #define KEYCODE_NUM_MINUS 0x2D // CLAW_GRIP_CLOSE
00031 #define KEYCODE_NUM_PLUS  0x2B // CLAW_GRIP_OPEN
00032 
00033 // Lift control key codes
00034 #define KEYCODE_UP        0x41 // LIFT_UP
00035 #define KEYCODE_DOWN      0x42 // LIFT_DOWN
00036 
00037 // Other key codes
00038 #define KEYCODE_COMMA     0x2C // SPEED_DOWN
00039 #define KEYCODE_PERIOD    0x2E // SPEED_UP
00040 #define KEYCODE_BACKSPACE 0x7F // ALL_STOP
00041 #define KEYCODE_TAB       0x09 // QUERY
00042 #define KEYCODE_Q         0x71 // QUIT
00043 
00053 class TeleopArmKey
00054 {
00055 public:
00056     TeleopArmKey();
00057 
00058 private:
00059     void init();
00060     void keyLoop();
00061     bool getCommand(const char c);
00062     void print();
00063       
00064     ros::NodeHandle n_;
00065     ros::Publisher cmd_pub_;
00066     arm::constant_move cmd_;
00067 };
00068 
00069 #endif


arm
Author(s): Jonathan Hasenzahl
autogenerated on Sun Jan 5 2014 11:12:32