H3D API
2.4.1
|
A ForceDimensionDevice is a node for handling communication with a haptics device from ForceDimension, such as the Omega and Delta haptics devices. More...
#include <H3D/ForceDimensionDevice.h>
Classes | |
class | Brakes |
Brakes specializes SFBool to toggle brakes on and off. More... | |
class | ChangeVibration |
EnableForce specializes SFFloat to handle vibration. More... | |
class | EffectorMass |
EffectorMass specializes SFFloat to change the end effector mass at change of value. More... | |
class | EnableForce |
EnableForce specializes SFBool to toggle forces on and off. More... | |
class | GravityComp |
GravityComp specializes SFBool to toggle gravity compensation on and off. More... | |
class | Reset |
Reset specializes SFBool to go into reset mode when a true event is received. More... | |
class | SFAutoCalibrate |
SFAutoCalibrate specializes SFBool to go into auto calibrate mode when a true event is received. More... | |
class | SFReleasePosition |
SFReleasePosition specializes SFVec3d to go set the release position of the contained haptics device. More... | |
class | WaitReset |
WaitReset specializes SFBool to go into wait on reset mode when a true event is received. More... | |
Public Member Functions | |
ForceDimensionDevice (Inst< SFVec3f > _devicePosition=0, Inst< SFRotation > _deviceOrientation=0, Inst< TrackerPosition > _trackerPosition=0, Inst< TrackerOrientation > _trackerOrientation=0, Inst< SFMatrix4f > _positionCalibration=0, Inst< SFRotation > _orientationCalibration=0, Inst< SFVec3f > _proxyPosition=0, Inst< WeightedProxy > _weightedProxyPosition=0, Inst< SFFloat > _proxyWeighting=0, Inst< SFBool > _mainButton=0, Inst< SFBool > _secondaryButton=0, Inst< SFInt32 > _buttons=0, Inst< SFVec3f > _force=0, Inst< SFVec3f > _torque=0, Inst< SFInt32 > _inputDOF=0, Inst< SFInt32 > _outputDOF=0, Inst< SFInt32 > _hapticsRate=0, Inst< SFInt32 > _desiredHapticsRate=0, Inst< SFNode > _stylus=0, Inst< SFHapticsRendererNode > _hapticsRenderer=0, Inst< MFVec3f > _proxyPositions=0, Inst< SFBool > _followViewpoint=0, Inst< GravityComp > _useGravityCompensation=0, Inst< Reset > _reset=0, Inst< WaitReset > _waitForReset=0, Inst< EffectorMass > _endEffectorMass=0, Inst< Brakes > _useBrakes=0, Inst< SFInt32 > _deviceType=0, Inst< EnableForce > _enableForce=0, Inst< SFFloat > _vibrationFrequency=0, Inst< SFFloat > _vibrationAmplitude=0, Inst< SFFloat > _gripperAngle=0, Inst< SFAutoCalibrate > _autoCalibrate=0, Inst< SFBool > _isAutoCalibrated=0, Inst< SFInt32 > _desiredComThreadRate=0, Inst< SFFloat > _gripperForce=0, Inst< SFBool > _flipGripperValues=0, Inst< SFReleasePosition > _releaseDevicePosition=0) | |
Constructor. | |
virtual ErrorCode | initDevice () |
Does all the initialization needed for the device before starting to use it. | |
virtual ErrorCode | releaseDevice () |
Perform cleanup and let go of all device resources that are allocated. More... | |
virtual void | updateDeviceValues () |
This function is used to transfer device values, such as position, button status etc from the realtime loop to the fields of H3DHapticsDevice, and possible vice versa. More... | |
virtual void | initialize () |
Creates a ForceDimensionHapticsDevice in the hapi_device with deviceType. | |
![]() | |
H3DHapticsDevice (Inst< SFVec3f > _devicePosition=0, Inst< SFRotation > _deviceOrientation=0, Inst< TrackerPosition > _trackerPosition=0, Inst< TrackerOrientation > _trackerOrientation=0, Inst< SFMatrix4f > _positionCalibration=0, Inst< SFRotation > _orientationCalibration=0, Inst< SFVec3f > _proxyPosition=0, Inst< WeightedProxy > _weightedProxyPosition=0, Inst< SFFloat > _proxyWeighting=0, Inst< SFBool > _mainButton=0, Inst< SFBool > _secondaryButton=0, Inst< SFInt32 > _buttons=0, Inst< SFVec3f > _force=0, Inst< SFVec3f > _torque=0, Inst< SFInt32 > _inputDOF=0, Inst< SFInt32 > _outputDOF=0, Inst< SFInt32 > _hapticsRate=0, Inst< SFInt32 > _desiredHapticsRate=0, Inst< SFNode > _stylus=0, Inst< SFHapticsRendererNode > _hapticsRenderer=0, Inst< MFVec3f > _proxyPositions=0, Inst< SFBool > _followViewpoint=0, Inst< SFVec3f > _deviceVelocity=0, Inst< TrackerVelocity > _trackerVelocity=0, Inst< SFString > _profiledResult=0, Inst< SFVec3f > _deviceAngularVelocity=0, Inst< TrackerAngularVelocity > _trackerAngularVelocity=0) | |
Constructor. | |
virtual | ~H3DHapticsDevice () |
Destuctor. | |
Vec3f | getPreviousProxyPosition (unsigned int layer=0) |
Get the proxy position from the previous loop for a certain layer. More... | |
const vector< Vec3f > & | getPreviousProxyPositions () |
Get all previous proxy positions. | |
virtual string | defaultXMLContainerField () |
Returns the default xml containerField attribute value. More... | |
HAPI::HAPIHapticsDevice * | getHAPIDevice () |
Get the HAPIHapticsDevice that is encapsulated by this node. | |
virtual ErrorCode | enableDevice () |
Enable the device. Positions can be read and force can be sent. | |
virtual ErrorCode | disableDevice () |
Temporarily disable the device. More... | |
H3DUtil::PeriodicThreadBase * | getThread () |
Get the thread that is used to run this haptics device. | |
virtual void | postInit () |
This function is called for all devices in a DeviceInfo node for which the initDevice has been called. More... | |
virtual void | preRender () |
This function is called at the start of each scenegraph loop before any calls to other HapticDevice functions and can be used to perform any necessary operation that are needed for the other calls to function properly. | |
virtual void | postRender () |
This function is called at the end of each scenegraph loop after all calls to other HapticDevice functions and can be used to perform any necessary operation that are needed. | |
virtual void | renderShapes (const HapticShapeVector &shapes, unsigned int layer=0) |
Perform haptic rendering for the given HapticShape instances. More... | |
virtual void | renderStylus () |
Render the stylus of the device wint OpenGL. | |
virtual void | renderEffects (const HapticEffectVector &effects) |
Perform haptic rendering for the given HAPIForceEffect instances. More... | |
![]() | |
Node () | |
Constructor. | |
virtual Node * | clone (bool deepCopy=true, DeepCopyMap *deepCopyMap=NULL) |
Returns a new instance of this node type with the same state as this one. More... | |
virtual | ~Node () |
Destructor. | |
X3DPrototypeInstance * | getProtoInstanceParent () |
If this node is the root node in the proto body of a X3DPrototypeInstance then this will return that node. More... | |
void | setProtoInstanceParent (X3DPrototypeInstance *p) |
Set the X3DPrototypeInstance this node is the the root node if applicaple. | |
virtual void | render () |
the render() function is used for the depth-first rendering traversal of the scene-graph. More... | |
virtual void | traverseSG (TraverseInfo &ti) |
traverseSG is called once per scenegraph loop on the scene in order to traverse the scenegraph. More... | |
virtual bool | lineIntersect (const Vec3f &from, const Vec3f &to, LineIntersectResult &result) |
Detect intersection between a line segment and the Node. More... | |
virtual void | closestPoint (const Vec3f &p, NodeIntersectResult &result) |
Find closest point on Node to p. More... | |
virtual bool | movingSphereIntersect (H3DFloat radius, const Vec3f &from, const Vec3f &to, NodeIntersectResult &result) |
Detect collision between a moving sphere and the Node. More... | |
virtual Field * | getField (const string &_name) const |
return a pointer to the field specified by name within this instance | |
int | addDestructCallback (void(*func)(Node *, void *), void *args) |
Add a callback function to be run on destruction of node. More... | |
int | removeDestructCallback (void(*func)(Node *, void *), void *args) |
Add a callback function to be run on destruction of node. More... | |
Public Attributes | |
H3DUniquePtr< SFBool > | useGravityCompensation |
Enable/disable gravity compensation. More... | |
H3DUniquePtr< Reset > | reset |
When a true event is received, the device is put into RESET mode. More... | |
H3DUniquePtr< WaitReset > | waitForReset |
When a true event is received, the device is put into RESET mode and wait for the user to calibrate the device. More... | |
H3DUniquePtr< SFFloat > | endEffectorMass |
Set the end effector mass used in gravity compensation in order to provide accurate gravity compensation when custom-made or modified end-effectors are used. More... | |
H3DUniquePtr< SFBool > | useBrakes |
Enable/disable the device electromagnetic brakes. More... | |
H3DUniquePtr< SFInt32 > | deviceType |
Contains the device type of the Force Dimension device. More... | |
H3DUniquePtr< EnableForce > | enableForce |
On some (custom) devices from force dimension there is no button to enable/disable forces on the device. More... | |
H3DUniquePtr< SFFloat > | vibrationFrequency |
On some (custom) devices from force dimension there are vibration support. More... | |
H3DUniquePtr< SFFloat > | vibrationAmplitude |
On some (custom) devices from force dimension there are vibration support. More... | |
H3DUniquePtr< SFFloat > | gripperAngle |
Output field for the gripper angle. More... | |
H3DUniquePtr< SFAutoCalibrate > | autoCalibrate |
When a true event is received, the device is auto calibrated. More... | |
H3DUniquePtr< SFBool > | isAutoCalibrated |
Indicates whether the device is calibrated. More... | |
H3DUniquePtr< SFInt32 > | desiredComThreadRate |
The desired frequency for the thread that communicates with the haptics device. More... | |
H3DUniquePtr< SFFloat > | gripperForce |
Output field for the gripper force. More... | |
H3DUniquePtr< SFBool > | flipGripperValues |
If true then the gripper angle output is negated with respect to what the underlying dhd api reports. More... | |
H3DUniquePtr< SFReleasePosition > | releaseDevicePosition |
If this value is set, and HAPI was compiled with DRD support then when the device is released the device will be moved to this position. More... | |
![]() | |
H3DUniquePtr< SFVec3f > | devicePosition |
The position of the device given in the coordinate system of the device. More... | |
H3DUniquePtr< SFRotation > | deviceOrientation |
The orientation of the device given in the coordinate system of the device. More... | |
H3DUniquePtr< TrackerPosition > | trackerPosition |
The position of the device in the world coordinates of the API. More... | |
H3DUniquePtr< TrackerOrientation > | trackerOrientation |
The orientation of the device in the world coordinates of the API. More... | |
H3DUniquePtr< SFMatrix4f > | positionCalibration |
The calibration matrix between devicePosition and trackerPosition. More... | |
H3DUniquePtr< SFMatrix4f > | adjustedPositionCalibration |
The calibration matrix between devicePosition and trackerPosition adjusted with the movement of the viewpoint. | |
H3DUniquePtr< SFRotation > | orientationCalibration |
The calibration rotation between deviceOrientation and trackerOrientation. More... | |
H3DUniquePtr< SFRotation > | adjustedOrnCalibration |
The calibration rotation between deviceOrientation and trackerOrientation adjusted with the movement of the viewpoint. | |
H3DUniquePtr< SFVec3f > | proxyPosition |
The position of the proxy used in the haptic rendering(layer 0). More... | |
H3DUniquePtr< WeightedProxy > | weightedProxyPosition |
A weighted position between proxyPosition and trackerPosition. More... | |
H3DUniquePtr< SFFloat > | proxyWeighting |
The weighting between proxyPosition and trackerPosition when calculating weightedProxyPosition. More... | |
H3DUniquePtr< SFBool > | mainButton |
The state of the main button(button 0). More... | |
H3DUniquePtr< SFBool > | secondaryButton |
The state of the secondary button (button 1). More... | |
H3DUniquePtr< SFInt32 > | buttons |
The state of all buttons. More... | |
H3DUniquePtr< SFVec3f > | force |
The approximation of the force that has been rendered during the last scenegraph loop. More... | |
H3DUniquePtr< SFVec3f > | torque |
The approximation of the torque that has been rendered during the last scenegraph loop. More... | |
H3DUniquePtr< SFInt32 > | inputDOF |
The degrees of freedom supported as input. More... | |
H3DUniquePtr< SFInt32 > | outputDOF |
The degrees of freedom supported as output, i.e. More... | |
H3DUniquePtr< SFInt32 > | hapticsRate |
The update rate of the servoloop of the H3DHapticsDevice. More... | |
H3DUniquePtr< SFInt32 > | desiredHapticsRate |
The desired update rate of the servoloop of the H3DHapticsDevice. More... | |
H3DUniquePtr< SFTime > | hapticsLoopTime |
The time spent in the last haptics loop(in seconds) A value of -1 means that no haptics loop has been completed yet. More... | |
H3DUniquePtr< SFNode > | stylus |
The Node used as the visual representation of the stylus. More... | |
H3DUniquePtr< SFBool > | initialized |
true if the device is initialized and ready for calls to updateDeviceValues() and renderObjects(). More... | |
H3DUniquePtr< SFHapticsRendererNode > | hapticsRenderer |
Specifies the haptics rendering algorithm to use to generate forces from geometric shapes. More... | |
H3DUniquePtr< MFVec3f > | proxyPositions |
The positions of the proxies for each layer used in haptic rendering(layer 0). More... | |
H3DUniquePtr< SetEnabled > | set_enabled |
Enable/disable the device. More... | |
H3DUniquePtr< SFBool > | enabled |
true if the device is enabled, e.g. More... | |
H3DUniquePtr< SFBool > | followViewpoint |
true if the device should follow the viewpoint. More... | |
H3DUniquePtr< SFVec3f > | deviceVelocity |
The velocity of the device in the coordinate system of the device. More... | |
H3DUniquePtr< TrackerVelocity > | trackerVelocity |
The velocity of the device in the world coordinates of the API. More... | |
H3DUniquePtr< SFFloat > | forceLimit |
The maximum force(in N) we want the device to render. More... | |
H3DUniquePtr< SFFloat > | forceScale |
Set the scaling of the output force. More... | |
H3DUniquePtr< SFBool > | deadmansSwitch |
This is an alternative operational safety mode. More... | |
H3DUniquePtr< SFFloat > | torqueLimit |
The maximum torque(in Nm) we want the device to render. More... | |
H3DUniquePtr< SFVec3f > | deviceAngularVelocity |
The angular velocity of the device in the coordinate system of the device. More... | |
H3DUniquePtr< TrackerAngularVelocity > | trackerAngularVelocity |
The angular velocity of the device in the world coordinates of the API. More... | |
Static Public Attributes | |
static H3DNodeDatabase | database |
Node database entry. | |
![]() | |
static H3DNodeDatabase | database |
Node database entry. | |
Additional Inherited Members | |
![]() | |
typedef SFMatrix4f | PosCalibration |
typedef SFRotation | OrnCalibration |
![]() | |
typedef std::map< Node *, Node * > | DeepCopyMap |
A map type used during a deep copy clone() to map from original nodes to cloned nodes. | |
![]() | |
static unsigned int | nrNodesAlive () |
Returns the nr of nodes currently alive, i.e. nodes created but not destructed. | |
static int | nrNodesCreated () |
Returns the number of nodes created in total since the start of the program. | |
![]() | |
void | cloneFieldValue (Field &_from, Field &_to, bool deepCopy, DeepCopyMap &deepCopyMap) |
A helper function for the clone() method. More... | |
![]() | |
static Node * | getClonedInstance (Node *original, bool deepCopy, DeepCopyMap &deepCopyMap) |
A helper function for nodes that implement clone() More... | |
![]() | |
TimeStamp | last_effect_change |
The time for the last call to the renderEffects function. | |
A ForceDimensionDevice is a node for handling communication with a haptics device from ForceDimension, such as the Omega and Delta haptics devices.
Examples:
|
virtual |
Perform cleanup and let go of all device resources that are allocated.
After a call to this function no haptic rendering can be performed on the device until the initDevice() function has been called again.
Reimplemented from H3D::H3DHapticsDevice.
References H3D::H3DHapticsDevice::releaseDevice().
|
virtual |
This function is used to transfer device values, such as position, button status etc from the realtime loop to the fields of H3DHapticsDevice, and possible vice versa.
Overridden to transfer gripper angle.
Reimplemented from H3D::H3DHapticsDevice.
References gripperAngle, gripperForce, isAutoCalibrated, and H3D::H3DHapticsDevice::updateDeviceValues().
H3DUniquePtr< SFAutoCalibrate > H3D::ForceDimensionDevice::autoCalibrate |
When a true event is received, the device is auto calibrated.
This will not do anything unless H3DAPI is compiled with DRD api support (HAVE_DRDAPI defined). After the device is calibrated forces will be enabled.
Access type: inputOnly
Default value: false
Referenced by ForceDimensionDevice(), and initDevice().
H3DUniquePtr< SFInt32 > H3D::ForceDimensionDevice::desiredComThreadRate |
The desired frequency for the thread that communicates with the haptics device.
If value is -1 then the communication is done directly in the haptics thread otherwise the communication is done in a separate thread at the given rate and locks are used to transfer values to the haptics thread.
Access type: initializeOnly
Default value type: 1000
Referenced by ForceDimensionDevice(), and initDevice().
H3DUniquePtr< SFInt32 > H3D::ForceDimensionDevice::deviceType |
Contains the device type of the Force Dimension device.
Possible values are:
Access type: inputOutput
Default type: -1
Referenced by ForceDimensionDevice(), initDevice(), and initialize().
H3DUniquePtr< EnableForce > H3D::ForceDimensionDevice::enableForce |
On some (custom) devices from force dimension there is no button to enable/disable forces on the device.
Therefore it might be useful to be able to do this programatically to be able to use the device. This is the field to use in that case. Note that this field will not be kept accurate if there is a button on the device to enable/disable forces and might in such cases be out of sync with the actual state.
Access type: inputOutput
Default value: false
Referenced by ForceDimensionDevice(), and initDevice().
H3DUniquePtr< SFFloat > H3D::ForceDimensionDevice::endEffectorMass |
Set the end effector mass used in gravity compensation in order to provide accurate gravity compensation when custom-made or modified end-effectors are used.
Access type: inputOnly
H3DUniquePtr< SFBool > H3D::ForceDimensionDevice::flipGripperValues |
If true then the gripper angle output is negated with respect to what the underlying dhd api reports.
Same thing happens for the gripper force. Might be useful in some cases when there are two devices of a different type that should control a similar feature. with the gripper angles.
Access type: inputOutput
Default value: false
Referenced by ForceDimensionDevice(), and initialize().
H3DUniquePtr< SFFloat > H3D::ForceDimensionDevice::gripperAngle |
Output field for the gripper angle.
Angle is in radians.
Access type: outputOnly
Referenced by ForceDimensionDevice(), and updateDeviceValues().
H3DUniquePtr< SFFloat > H3D::ForceDimensionDevice::gripperForce |
Output field for the gripper force.
Force is in Newton
Access type: outputOnly
Referenced by ForceDimensionDevice(), and updateDeviceValues().
H3DUniquePtr< SFBool > H3D::ForceDimensionDevice::isAutoCalibrated |
Indicates whether the device is calibrated.
Access type: outputOnly
Referenced by ForceDimensionDevice(), and updateDeviceValues().
H3DUniquePtr< SFReleasePosition > H3D::ForceDimensionDevice::releaseDevicePosition |
If this value is set, and HAPI was compiled with DRD support then when the device is released the device will be moved to this position.
Note that the position is given in device space. If this field is not set explicitly by the user then the device will not move to any position when released.
Access type: inputOutput
Default value: Vec3d( 0, 0, 0 )
Referenced by initialize().
H3DUniquePtr< Reset > H3D::ForceDimensionDevice::reset |
When a true event is received, the device is put into RESET mode.
In this mode, the user is expected to put the device end-effector at its rest position. This is how the device performs its calibration.
Access type: inputOnly
H3DUniquePtr< SFBool > H3D::ForceDimensionDevice::useBrakes |
Enable/disable the device electromagnetic brakes.
If enabled the device motor circuits are shortcut to produce electromagnetic viscosity. The viscosity is sufficient to prevent the device from falling too hard onto if forces are disabled abruptly, either by pressing the force button or by action of a safety feature.
Access type: inputOutput
Default value: true
Referenced by ForceDimensionDevice().
H3DUniquePtr< SFBool > H3D::ForceDimensionDevice::useGravityCompensation |
Enable/disable gravity compensation.
A value of true enables it. When gravity compensation is enabled, the weights of the arms and of the end-effector are taken into account and a vertical force is dynamically applied to the end-effector on top of the user command.
Access type: inputOutput
Default value: true
Referenced by ForceDimensionDevice().
H3DUniquePtr< SFFloat > H3D::ForceDimensionDevice::vibrationAmplitude |
On some (custom) devices from force dimension there are vibration support.
This field is used to control the amplitude of the vibration. Negative values are clamped to 0 which means that vibrations is turned off. A value of 1 means that vibration is at full amplitude of the device.
Access type: inputOutput
Default value: 0
Valid values: [0, 1]
Referenced by ForceDimensionDevice().
H3DUniquePtr< SFFloat > H3D::ForceDimensionDevice::vibrationFrequency |
On some (custom) devices from force dimension there are vibration support.
This field is used to control the frequency of the vibration. Only used if vibrationAmplitude is above 0.
Access type: inputOutput
Default value: 100
Valid values: [0, inf]
Referenced by ForceDimensionDevice().
H3DUniquePtr< WaitReset > H3D::ForceDimensionDevice::waitForReset |
When a true event is received, the device is put into RESET mode and wait for the user to calibrate the device.
Access type: inputOnly