#include <HapticDeviceController.hpp>

Public Member Functions | |
| virtual void | didLeaveSpinLoop ()=0 | 
| virtual void | loopCB (const HapticOuput &output, HapticInput &input)=0 | 
| virtual void | setAxesMapping (HapticAxesMapping &xAxis, HapticAxesMapping &yAxis, HapticAxesMapping &zAxis)=0 | 
| virtual void | setAxesRange (const Position3D &minValues, const Position3D &maxValues)=0 | 
| virtual void | setIdentifier (const std::string &identifier)=0 | 
| virtual void | willEnterSpinLoop ()=0 | 
Definition at line 19 of file HapticDeviceController.hpp.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::didLeaveSpinLoop | ( | ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::loopCB | ( | const HapticOuput & | output, | 
| HapticInput & | input | ||
| ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::setAxesMapping | ( | HapticAxesMapping & | xAxis, | 
| HapticAxesMapping & | yAxis, | ||
| HapticAxesMapping & | zAxis | ||
| ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::setAxesRange | ( | const Position3D & | minValues, | 
| const Position3D & | maxValues | ||
| ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::setIdentifier | ( | const std::string & | identifier | ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.
| virtual void TELEKYB_NAMESPACE::HapticDeviceController::willEnterSpinLoop | ( | ) |  [pure virtual] | 
        
Implemented in telekyb_haptic::SampleController.