H3D API  2.4.1
Classes | Public Member Functions | Public Attributes | Static Public Attributes | List of all members
H3D::PhantomDevice Class Reference

A PhantomDevice is a node for handling communication with a haptics device from SensAble, such as the Phantom Omni and the Phantom Desktop haptics devices. More...

#include <H3D/PhantomDevice.h>

Inheritance diagram for H3D::PhantomDevice:
Inheritance graph

Classes

class  Calibrate
 Field class that calibrates the device when a true event is received or the field is set to true. More...
 

Public Member Functions

 PhantomDevice (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< SFString > _deviceName=0, Inst< SFBool > _inInkwell=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 ErrorCode enableDevice ()
 Enabling the device for a phantomdevice should be blocked if the scheduler hasn't been started yet, so we override enableDevice() to check it here.
 
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.
 
virtual void initialize ()
 Creates a PhantomHapticsDevice in the hapi_device with name deviceName.
 
virtual void postInit ()
 This function is called for all devices in a DeviceInfo node for which the initDevice has been called. More...
 
- Public Member Functions inherited from H3D::H3DHapticsDevice
 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 disableDevice ()
 Temporarily disable the device. More...
 
H3DUtil::PeriodicThreadBasegetThread ()
 Get the thread that is used to run this haptics device.
 
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...
 
- Public Member Functions inherited from H3D::Node
 Node ()
 Constructor.
 
virtual Nodeclone (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.
 
X3DPrototypeInstancegetProtoInstanceParent ()
 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 FieldgetField (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< SFStringdeviceName
 The name of the device, as specified in Phantom Configuration utility. More...
 
H3DUniquePtr< SFStringHDAPIVersion
 The HDAPI software version, in the form major.minor.build. More...
 
H3DUniquePtr< SFStringdeviceModelType
 The device model of the device. More...
 
H3DUniquePtr< SFStringdeviceDriverVersion
 The device driver version of the device. More...
 
H3DUniquePtr< SFDoubledeviceFirmwareVersion
 The device firmware version. More...
 
H3DUniquePtr< SFStringdeviceVendor
 The vendor of the device. More...
 
H3DUniquePtr< SFStringdeviceSerialNumber
 The serial number of the device. More...
 
H3DUniquePtr< MFVec3fmaxWorkspaceDimensions
 The maximum workspace dimensions of the device, i.e. More...
 
H3DUniquePtr< MFVec3fusableWorkspaceDimensions
 the usable workspace dimensions of the device, i.e. More...
 
H3DUniquePtr< SFFloattabletopOffset
 The mechanical offest of the device end-effector in y from the table top. More...
 
H3DUniquePtr< SFFloatmaxForce
 The maximum force, i.e. More...
 
H3DUniquePtr< SFFloatmaxContinuousForce
 The maximum continuous force, i.e. More...
 
H3DUniquePtr< SFVec3fgimbalAngles
 Current gimbal angles for the device (in radians). More...
 
H3DUniquePtr< SFVec3fjointAngles
 Current joint angles for the device (in radians). More...
 
H3DUniquePtr< SFBoolneedsCalibration
 This field is true if the device needs to be calibrated. More...
 
H3DUniquePtr< Calibratecalibrate
 When a true event is received, the calibration procedure for the device is started. More...
 
H3DUniquePtr< MFDoublemotorTemperatures
 Motor temperatures from the device driver temperature model. More...
 
H3DUniquePtr< MFDoubleencoderValues
 Raw encoder values for this device. More...
 
H3DUniquePtr< SFBoolinInkwell
 True when the device is in the inkwell. More...
 
- Public Attributes inherited from H3D::H3DHapticsDevice
H3DUniquePtr< SFVec3fdevicePosition
 The position of the device given in the coordinate system of the device. More...
 
H3DUniquePtr< SFRotationdeviceOrientation
 The orientation of the device given in the coordinate system of the device. More...
 
H3DUniquePtr< TrackerPositiontrackerPosition
 The position of the device in the world coordinates of the API. More...
 
H3DUniquePtr< TrackerOrientationtrackerOrientation
 The orientation of the device in the world coordinates of the API. More...
 
H3DUniquePtr< SFMatrix4fpositionCalibration
 The calibration matrix between devicePosition and trackerPosition. More...
 
H3DUniquePtr< SFMatrix4fadjustedPositionCalibration
 The calibration matrix between devicePosition and trackerPosition adjusted with the movement of the viewpoint.
 
H3DUniquePtr< SFRotationorientationCalibration
 The calibration rotation between deviceOrientation and trackerOrientation. More...
 
H3DUniquePtr< SFRotationadjustedOrnCalibration
 The calibration rotation between deviceOrientation and trackerOrientation adjusted with the movement of the viewpoint.
 
H3DUniquePtr< SFVec3fproxyPosition
 The position of the proxy used in the haptic rendering(layer 0). More...
 
H3DUniquePtr< WeightedProxyweightedProxyPosition
 A weighted position between proxyPosition and trackerPosition. More...
 
H3DUniquePtr< SFFloatproxyWeighting
 The weighting between proxyPosition and trackerPosition when calculating weightedProxyPosition. More...
 
H3DUniquePtr< SFBoolmainButton
 The state of the main button(button 0). More...
 
H3DUniquePtr< SFBoolsecondaryButton
 The state of the secondary button (button 1). More...
 
H3DUniquePtr< SFInt32buttons
 The state of all buttons. More...
 
H3DUniquePtr< SFVec3fforce
 The approximation of the force that has been rendered during the last scenegraph loop. More...
 
H3DUniquePtr< SFVec3ftorque
 The approximation of the torque that has been rendered during the last scenegraph loop. More...
 
H3DUniquePtr< SFInt32inputDOF
 The degrees of freedom supported as input. More...
 
H3DUniquePtr< SFInt32outputDOF
 The degrees of freedom supported as output, i.e. More...
 
H3DUniquePtr< SFInt32hapticsRate
 The update rate of the servoloop of the H3DHapticsDevice. More...
 
H3DUniquePtr< SFInt32desiredHapticsRate
 The desired update rate of the servoloop of the H3DHapticsDevice. More...
 
H3DUniquePtr< SFTimehapticsLoopTime
 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< SFNodestylus
 The Node used as the visual representation of the stylus. More...
 
H3DUniquePtr< SFBoolinitialized
 true if the device is initialized and ready for calls to updateDeviceValues() and renderObjects(). More...
 
H3DUniquePtr< SFHapticsRendererNodehapticsRenderer
 Specifies the haptics rendering algorithm to use to generate forces from geometric shapes. More...
 
H3DUniquePtr< MFVec3fproxyPositions
 The positions of the proxies for each layer used in haptic rendering(layer 0). More...
 
H3DUniquePtr< SetEnabledset_enabled
 Enable/disable the device. More...
 
H3DUniquePtr< SFBoolenabled
 true if the device is enabled, e.g. More...
 
H3DUniquePtr< SFBoolfollowViewpoint
 true if the device should follow the viewpoint. More...
 
H3DUniquePtr< SFVec3fdeviceVelocity
 The velocity of the device in the coordinate system of the device. More...
 
H3DUniquePtr< TrackerVelocitytrackerVelocity
 The velocity of the device in the world coordinates of the API. More...
 
H3DUniquePtr< SFFloatforceLimit
 The maximum force(in N) we want the device to render. More...
 
H3DUniquePtr< SFFloatforceScale
 Set the scaling of the output force. More...
 
H3DUniquePtr< SFBooldeadmansSwitch
 This is an alternative operational safety mode. More...
 
H3DUniquePtr< SFFloattorqueLimit
 The maximum torque(in Nm) we want the device to render. More...
 
H3DUniquePtr< SFVec3fdeviceAngularVelocity
 The angular velocity of the device in the coordinate system of the device. More...
 
H3DUniquePtr< TrackerAngularVelocitytrackerAngularVelocity
 The angular velocity of the device in the world coordinates of the API. More...
 

Static Public Attributes

static H3DNodeDatabase database
 Node database entry.
 
- Static Public Attributes inherited from H3D::H3DHapticsDevice
static H3DNodeDatabase database
 Node database entry.
 

Additional Inherited Members

- Public Types inherited from H3D::H3DHapticsDevice
typedef SFMatrix4f PosCalibration
 
typedef SFRotation OrnCalibration
 
- Public Types inherited from H3D::Node
typedef std::map< Node *, Node * > DeepCopyMap
 A map type used during a deep copy clone() to map from original nodes to cloned nodes.
 
- Static Public Member Functions inherited from H3D::Node
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.
 
- Protected Member Functions inherited from H3D::Node
void cloneFieldValue (Field &_from, Field &_to, bool deepCopy, DeepCopyMap &deepCopyMap)
 A helper function for the clone() method. More...
 
- Static Protected Member Functions inherited from H3D::Node
static NodegetClonedInstance (Node *original, bool deepCopy, DeepCopyMap &deepCopyMap)
 A helper function for nodes that implement clone() More...
 
- Protected Attributes inherited from H3D::H3DHapticsDevice
TimeStamp last_effect_change
 The time for the last call to the renderEffects function.
 

Detailed Description

A PhantomDevice is a node for handling communication with a haptics device from SensAble, such as the Phantom Omni and the Phantom Desktop haptics devices.

Note: The valid values for desiredHapticsRate depends on the type of interface and communication protocol used. Frequencies of 500, 1000, and 2000 Hz are valid when using a device connecting through PCI and EPP. Frequencies of 500, 1000, 1600Hz plus values in between based on the formula floor(8000/N + 0.5) are valid for devices connecting through Firewire. The first successful initialization of PhantomDevice will decide the haptics thread rate since only one scheduler is used by OpenHaptics even for dual device configurations. The default value for the field desiredHapticsRate is different from the default value of H3DHapticsDevice since the allowed values of this field differs. If the value for desiredHapticsRate is not one of the valid values a warning about not being able to start or maintain the scheduler will be printed. The node will function properly anyways.

Examples:

Member Function Documentation

◆ postInit()

void PhantomDevice::postInit ( )
virtual

This function is called for all devices in a DeviceInfo node for which the initDevice has been called.

It is not called until all initDevice calls have been completed for all devices in the DeviceInfo. This function can be used for functionality that require all devices to be initialized. For this node it is used to start the OpenHaptics scheduler.

Reimplemented from H3D::H3DHapticsDevice.

References enableDevice().

◆ releaseDevice()

H3DHapticsDevice::ErrorCode PhantomDevice::releaseDevice ( )
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().

Member Data Documentation

◆ calibrate

H3DUniquePtr< Calibrate > H3D::PhantomDevice::calibrate

When a true event is received, the calibration procedure for the device is started.

The calibration procedure depends on the device type.

Access type: inputOnly

◆ deviceDriverVersion

H3DUniquePtr< SFString > H3D::PhantomDevice::deviceDriverVersion

The device driver version of the device.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice().

◆ deviceFirmwareVersion

H3DUniquePtr< SFDouble > H3D::PhantomDevice::deviceFirmwareVersion

The device firmware version.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().

◆ deviceModelType

H3DUniquePtr< SFString > H3D::PhantomDevice::deviceModelType

The device model of the device.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice().

◆ deviceName

H3DUniquePtr< SFString > H3D::PhantomDevice::deviceName

The name of the device, as specified in Phantom Configuration utility.

If set to "", the default device will be used.

Access type: initializeOnly
Default value: ""

Referenced by initialize().

◆ deviceSerialNumber

H3DUniquePtr< SFString > H3D::PhantomDevice::deviceSerialNumber

The serial number of the device.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice().

◆ deviceVendor

H3DUniquePtr< SFString > H3D::PhantomDevice::deviceVendor

The vendor of the device.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice().

◆ encoderValues

H3DUniquePtr< MFDouble > H3D::PhantomDevice::encoderValues

Raw encoder values for this device.

This will contain 6 values. See the OpenHaptics SDK documentation for more information about encoder values.

Access type: outputOnly

Referenced by PhantomDevice(), and updateDeviceValues().

◆ gimbalAngles

H3DUniquePtr< SFVec3f > H3D::PhantomDevice::gimbalAngles

Current gimbal angles for the device (in radians).

From neutral position:

  • x - Right = +
  • y - Up = -
  • z - Clockwise = +

Access type: outputOnly

Referenced by updateDeviceValues().

◆ HDAPIVersion

H3DUniquePtr< SFString > H3D::PhantomDevice::HDAPIVersion

The HDAPI software version, in the form major.minor.build.

Access type: outputOnly

Referenced by initDevice().

◆ inInkwell

H3DUniquePtr< SFBool > H3D::PhantomDevice::inInkwell

True when the device is in the inkwell.

Access type: outputOnly

Referenced by initDevice(), PhantomDevice(), and updateDeviceValues().

◆ jointAngles

H3DUniquePtr< SFVec3f > H3D::PhantomDevice::jointAngles

Current joint angles for the device (in radians).

  • x - turret, + = left
  • y - thigh, + = up
  • z - shin, + = up

Access type: outputOnly

Referenced by updateDeviceValues().

◆ maxContinuousForce

H3DUniquePtr< SFFloat > H3D::PhantomDevice::maxContinuousForce

The maximum continuous force, i.e.

the amount of force that the device can sustain through a period of time. Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().

◆ maxForce

H3DUniquePtr< SFFloat > H3D::PhantomDevice::maxForce

The maximum force, i.e.

the amount of force that the device can sustain when the motors are at room temperature Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().

◆ maxWorkspaceDimensions

H3DUniquePtr< MFVec3f > H3D::PhantomDevice::maxWorkspaceDimensions

The maximum workspace dimensions of the device, i.e.

the mechanical limits of the device. Undefined if device not initialized. Contains two values where the first value is the minimum values and the second the maximum values for each axis.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().

◆ motorTemperatures

H3DUniquePtr< MFDouble > H3D::PhantomDevice::motorTemperatures

Motor temperatures from the device driver temperature model.

It contains 6 values where the first 3 values are motor for position control and the rest are for torque control. The values are normalized between 0 and 1 where 0 means cool and 1 the temperature where the driver will shut down the motors for a few seconds to allow them to cool a bit.

Access type: outputOnly

Referenced by PhantomDevice(), and updateDeviceValues().

◆ needsCalibration

H3DUniquePtr< SFBool > H3D::PhantomDevice::needsCalibration

This field is true if the device needs to be calibrated.

Access type: outputOnly

Referenced by initDevice(), PhantomDevice(), and updateDeviceValues().

◆ tabletopOffset

H3DUniquePtr< SFFloat > H3D::PhantomDevice::tabletopOffset

The mechanical offest of the device end-effector in y from the table top.

Undefined if device not initialized.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().

◆ usableWorkspaceDimensions

H3DUniquePtr< MFVec3f > H3D::PhantomDevice::usableWorkspaceDimensions

the usable workspace dimensions of the device, i.e.

the workspace in which forces are guaranteed to be reliably render. Undefined if device not initialized. Contains two values where the first value is the minimum values and the second the maximum values for each axis.

Access type: outputOnly

Referenced by initDevice(), and PhantomDevice().


The documentation for this class was generated from the following files: