H3D API  2.4.1
PhantomDevice.h
Go to the documentation of this file.
1 // Copyright 2004-2019, SenseGraphics AB
3 //
4 // This file is part of H3D API.
5 //
6 // H3D API is free software; you can redistribute it and/or modify
7 // it under the terms of the GNU General Public License as published by
8 // the Free Software Foundation; either version 2 of the License, or
9 // (at your option) any later version.
10 //
11 // H3D API is distributed in the hope that it will be useful,
12 // but WITHOUT ANY WARRANTY; without even the implied warranty of
13 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 // GNU General Public License for more details.
15 //
16 // You should have received a copy of the GNU General Public License
17 // along with H3D API; if not, write to the Free Software
18 // Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
19 //
20 // A commercial license is also available. Please contact us at
21 // www.sensegraphics.com for more information.
22 //
23 //
27 //
29 #ifndef __PHANTOMDEVICE_H__
30 #define __PHANTOMDEVICE_H__
31 
32 #include <H3D/H3DHapticsDevice.h>
33 #include <H3D/MFString.h>
34 #include <H3D/SFString.h>
35 #include <H3D/SFDouble.h>
36 #include <H3D/MFVec3f.h>
37 #include <H3D/MFDouble.h>
38 
39 namespace H3D {
40 
63  class H3DAPI_API PhantomDevice: public H3DHapticsDevice {
64  public:
65 
68  class H3DAPI_API Calibrate: public AutoUpdate< OnValueChangeSField< SFBool > > {
69  virtual void onValueChange( const bool &_value );
70  };
71 
74  Inst< SFVec3f > _devicePosition = 0,
75  Inst< SFRotation > _deviceOrientation = 0,
76  Inst< TrackerPosition > _trackerPosition = 0,
77  Inst< TrackerOrientation > _trackerOrientation = 0,
78  Inst< SFMatrix4f > _positionCalibration = 0,
79  Inst< SFRotation > _orientationCalibration = 0,
80  Inst< SFVec3f > _proxyPosition = 0,
81  Inst< WeightedProxy > _weightedProxyPosition = 0,
82  Inst< SFFloat > _proxyWeighting = 0,
83  Inst< SFBool > _mainButton = 0,
84  Inst< SFBool > _secondaryButton = 0,
85  Inst< SFInt32 > _buttons = 0,
86  Inst< SFVec3f > _force = 0,
87  Inst< SFVec3f > _torque = 0,
88  Inst< SFInt32 > _inputDOF = 0,
89  Inst< SFInt32 > _outputDOF = 0,
90  Inst< SFInt32 > _hapticsRate = 0,
91  Inst< SFInt32 > _desiredHapticsRate = 0,
92  Inst< SFNode > _stylus = 0,
93  Inst< SFString > _deviceName = 0,
94  Inst< SFBool > _inInkwell = 0 );
95 
98  virtual ErrorCode initDevice();
99 
103  virtual ErrorCode releaseDevice();
104 
105 
107  virtual ErrorCode enableDevice();
108 
112  virtual void updateDeviceValues();
113 
116  virtual void initialize();
117 
123  virtual void postInit();
124 
130  H3DUniquePtr< SFString > deviceName;
131 
135  H3DUniquePtr< SFString > HDAPIVersion;
136 
141  H3DUniquePtr< SFString > deviceModelType;
142 
147  H3DUniquePtr< SFString > deviceDriverVersion;
148 
153  H3DUniquePtr< SFDouble > deviceFirmwareVersion;
154 
159  H3DUniquePtr< SFString > deviceVendor;
160 
165  H3DUniquePtr< SFString > deviceSerialNumber;
166 
174  H3DUniquePtr< MFVec3f > maxWorkspaceDimensions;
175 
183  H3DUniquePtr< MFVec3f > usableWorkspaceDimensions;
184 
189  H3DUniquePtr< SFFloat > tabletopOffset;
190 
196  H3DUniquePtr< SFFloat > maxForce;
197 
203  H3DUniquePtr< SFFloat > maxContinuousForce;
204 
212  H3DUniquePtr< SFVec3f > gimbalAngles;
213 
220  H3DUniquePtr< SFVec3f > jointAngles;
221 
225  H3DUniquePtr< SFBool > needsCalibration;
226 
232  H3DUniquePtr< Calibrate > calibrate;
233 
241  H3DUniquePtr< MFDouble > motorTemperatures;
242 
248  H3DUniquePtr< MFDouble > encoderValues;
249 
253  H3DUniquePtr< SFBool > inInkwell;
254 
257 
258  protected:
259  static unsigned int nr_initialized_devices;
260  static bool started_scheduler;
261  static unsigned int render_shapes_called;
262  };
263 }
264 
265 #endif
Header file for H3DHapticsDevice.
Contains the MFDouble field class.
Contains the MFString field class.
Contains the MFVec3f field class.
Contains the SFDouble field class.
Contains the SFString field class.
Base class for all haptic devices.
Definition: H3DHapticsDevice.h:68
Field class that calibrates the device when a true event is received or the field is set to true.
Definition: PhantomDevice.h:68
A PhantomDevice is a node for handling communication with a haptics device from SensAble,...
Definition: PhantomDevice.h:63
H3DUniquePtr< MFDouble > motorTemperatures
Motor temperatures from the device driver temperature model.
Definition: PhantomDevice.h:241
H3DUniquePtr< SFString > deviceModelType
The device model of the device.
Definition: PhantomDevice.h:141
static H3DNodeDatabase database
Node database entry.
Definition: PhantomDevice.h:256
H3DUniquePtr< SFBool > needsCalibration
This field is true if the device needs to be calibrated.
Definition: PhantomDevice.h:225
H3DUniquePtr< SFVec3f > gimbalAngles
Current gimbal angles for the device (in radians).
Definition: PhantomDevice.h:212
H3DUniquePtr< SFBool > inInkwell
True when the device is in the inkwell.
Definition: PhantomDevice.h:253
H3DUniquePtr< SFString > deviceSerialNumber
The serial number of the device.
Definition: PhantomDevice.h:165
H3DUniquePtr< MFDouble > encoderValues
Raw encoder values for this device.
Definition: PhantomDevice.h:248
H3DUniquePtr< SFString > deviceVendor
The vendor of the device.
Definition: PhantomDevice.h:159
H3DUniquePtr< SFFloat > maxContinuousForce
The maximum continuous force, i.e.
Definition: PhantomDevice.h:203
H3DUniquePtr< SFString > deviceName
The name of the device, as specified in Phantom Configuration utility.
Definition: PhantomDevice.h:130
H3DUniquePtr< SFString > deviceDriverVersion
The device driver version of the device.
Definition: PhantomDevice.h:147
H3DUniquePtr< Calibrate > calibrate
When a true event is received, the calibration procedure for the device is started.
Definition: PhantomDevice.h:232
H3DUniquePtr< MFVec3f > maxWorkspaceDimensions
The maximum workspace dimensions of the device, i.e.
Definition: PhantomDevice.h:174
H3DUniquePtr< MFVec3f > usableWorkspaceDimensions
the usable workspace dimensions of the device, i.e.
Definition: PhantomDevice.h:183
H3DUniquePtr< SFDouble > deviceFirmwareVersion
The device firmware version.
Definition: PhantomDevice.h:153
H3DUniquePtr< SFFloat > maxForce
The maximum force, i.e.
Definition: PhantomDevice.h:196
H3DUniquePtr< SFFloat > tabletopOffset
The mechanical offest of the device end-effector in y from the table top.
Definition: PhantomDevice.h:189
H3DUniquePtr< SFString > HDAPIVersion
The HDAPI software version, in the form major.minor.build.
Definition: PhantomDevice.h:135
H3DUniquePtr< SFVec3f > jointAngles
Current joint angles for the device (in radians).
Definition: PhantomDevice.h:220
H3D API namespace.
Definition: Anchor.h:38
The AutoUpdate field is a template to force the BaseField to update itself as soon as an event is rec...
Definition: FieldTemplates.h:130
The H3DNodeDatabase contains a mapping between a name of a Node and the constructor for the Node with...
Definition: H3DNodeDatabase.h:194