JoystickConfig.hpp
Go to the documentation of this file.
00001 /*
00002  * JoystickConfig.h
00003  *
00004  *  Created on: Oct 24, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef JOYSTICKCONFIG_HPP_
00009 #define JOYSTICKCONFIG_HPP_
00010 
00011 #include <telekyb_hid/HIDDevice.hpp>
00012 
00013 #include <sensor_msgs/Joy.h>
00014 
00015 #include <vector>
00016 
00017 namespace TELEKYB_NAMESPACE
00018 {
00019 
00020 struct JoyAxis {
00021         int bytePos;
00022         int min;
00023         int max;
00024         std::string name;
00025 };
00026 
00027 struct JoyButton {
00028         int bytePos;
00029         unsigned char value;
00030         unsigned char mask;
00031         std::string name;
00032 };
00033 
00034 
00035 class JoystickConfig {
00036 protected:
00037         std::vector<unsigned char> byteArray;
00038         std::vector<JoyAxis> axes;
00039         std::vector<JoyButton> buttons;
00040         float axisCutOff;
00041 
00042         std::vector<int> buttonRemapping;
00043         std::vector<int> axisRemapping;
00044         std::vector<double> axisMultiplier;
00045 
00046 public:
00047         JoystickConfig();
00048         virtual ~JoystickConfig();
00049 
00050         void setVectors(const std::vector<unsigned char>& byteArray_,
00051                         const std::vector<JoyAxis>& axes_, const std::vector<JoyButton>& buttons_);
00052         void setModifiers(const std::vector<int>& buttonRemapping_,
00053                         const std::vector<int>& axisRemapping_, const std::vector<double>& axisMultiplier_);
00054 
00055         void parseInput(unsigned char* input, sensor_msgs::Joy& joyMsg) const;
00056         void setAxisCutOff(float axisCutOff_);
00057 
00058 };
00059 
00060 
00061 } /* namespace telekyb */
00062 
00063 
00064 #endif /* JOYSTICKCONFIG_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_hid
Author(s): mriedel
autogenerated on Mon Nov 11 2013 11:14:51