Joystick.hpp
Go to the documentation of this file.
00001 /*
00002  * Joystick.hpp
00003  *
00004  *  Created on: Oct 24, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef JOYSTICK_HPP_
00009 #define JOYSTICK_HPP_
00010 
00011 #include <telekyb_hid/HIDDevice.hpp>
00012 #include <telekyb_hid/JoystickConfig.hpp>
00013 #include <telekyb_hid/JoystickOptions.hpp>
00014 
00015 #include <boost/thread.hpp>
00016 
00017 //ros
00018 #include <ros/publisher.h>
00019 
00020 #include <vector>
00021 
00022 namespace TELEKYB_NAMESPACE
00023 {
00024 
00025 class Joystick : public HIDDevice {
00026 protected:
00027         JoystickOptions* options; // singleton holder
00028         JoystickConfig config;
00029 
00030         std::string name;
00031 
00032         ros::NodeHandle nodeHandle;
00033         ros::Publisher pub; // output
00034         std::string frameID;
00035 
00036         // Thread
00037         boost::thread* thread;
00038 
00039         // main run loop
00040         void run(); // endless loop
00041 
00042 public:
00043         Joystick(unsigned short int vendorID_ , unsigned short int productID_, const std::string& name_);
00044         virtual ~Joystick();
00045 
00046         void setVectors(const std::vector<unsigned char>& byteArray_,
00047                         const std::vector<JoyAxis>& axes_, const std::vector<JoyButton>& buttons_);
00048 
00049         std::string getName() const;
00050         void setName(const std::string& name_);
00051 
00052         void startThread();
00053         void joinThread();
00054 
00055         static void getJoysticks(const std::string& filename, std::vector<Joystick*>& joysticks);
00056 };
00057 
00058 } /* namespace telekyb */
00059 #endif /* JOYSTICK_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


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