DHDDevice.hpp
Go to the documentation of this file.
00001 /*
00002  * DHDDevice.h
00003  *
00004  *  Created on: Sep 29, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef DHDDEVICE_HPP_
00009 #define DHDDEVICE_HPP_
00010 
00011 #include <ros/ros.h>
00012 #include <iostream>
00013 
00014 #include <boost/thread.hpp>
00015 
00016 #include <tk_haptics_base/HapticDeviceController.hpp>
00017 #include <pluginlib/class_loader.h>
00018 
00019 #include "DHDDeviceOptions.hpp"
00020 
00021 namespace TELEKYB_NAMESPACE
00022 {
00023 
00024 class DHDDevice {
00025 private:
00026         // ID of the Device
00027         int id;
00028         std::string name;
00029         std::string identifier;
00030         std::string longIdentifier;
00031 
00032         // Options
00033         DHDDeviceOptions *options;
00034 
00035         // Controller
00036         HapticDeviceController *controller;
00037 
00038         HapticInput input;
00039         HapticOuput output;
00040 
00041         // Params
00042         //DHDParams params;
00043         //Position3D offset;
00044         //double normFactor;
00045 
00046         // ROS
00047         ros::NodeHandle nodeHandle;
00048 
00049         // tk_haptics_msgs::TKHapticOutput Publisher
00050         ros::Publisher statusPub;
00051 
00052         // Thread
00053         boost::thread thread;
00054 
00055         // initializer before spin loop
00056         bool init();
00057         // the threaded function
00058         void spin();
00059 
00060 public:
00061         DHDDevice(int id_, bool alreadyOpen = false);
00062         virtual ~DHDDevice();
00063 
00064         std::string getLongIdentifier() const;
00065 
00066         // Thread stuff
00067         void startThread();
00068         void joinThread();
00069 
00070         void loadController(pluginlib::ClassLoader<HapticDeviceController>& controllerLoader);
00071 };
00072 
00073 } // Namespace
00074 
00075 #endif /* DHDDEVICE_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


dhd32_driver
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:14:43