00001
00002
00003
00004
00005
00006
00007
00008
00009
00011 #pragma once
00012
00013 #ifdef WIN32
00014
00015 #ifdef _EXPORTING
00016 #define CLASS_DECLSPEC __declspec(dllexport)
00017 #else
00018 #define CLASS_DECLSPEC __declspec(dllimport)
00019 #endif // _EXPORTING
00020
00021 #elif defined( __GNUC__ )
00022
00023 #if __GNUC__ < 4
00024 #error gcc 4 is required.
00025 #endif
00026 #define CLASS_DECLSPEC __attribute__((visibility("default")))
00027
00028 #else
00029
00030 #define CLASS_DECLSPEC
00031
00032 #endif
00033
00034 #include <string>
00035
00036 namespace ViconDataStreamSDK
00037 {
00038 namespace CPP
00039 {
00040
00041 class IStringFactory
00042 {
00043 public:
00044 virtual char * AllocAndCopyString( const char * i_pSource ) = 0;
00045 virtual void FreeString( char * i_pString ) = 0;
00046 protected:
00047 virtual ~IStringFactory() {}
00048 };
00049
00050 class String
00051 {
00052 public:
00053
00054 inline
00055 String( const char * i_pString = 0 )
00056 : m_pString( 0 )
00057 , m_pConstString( i_pString )
00058 , m_pStringFactory( 0 )
00059 {
00060 }
00061
00062
00063 String( const std::string & i_rString )
00064 : m_pString( 0 )
00065 , m_pConstString( i_rString.c_str() )
00066 , m_pStringFactory( 0 )
00067 {
00068 }
00069
00070
00071 inline
00072 String( const String & i_rString )
00073 {
00074 m_pConstString = i_rString.m_pConstString;
00075 m_pStringFactory = i_rString.m_pStringFactory;
00076 if( m_pStringFactory )
00077 {
00078 m_pString = m_pStringFactory->AllocAndCopyString( i_rString.m_pString );
00079 }
00080 else
00081 {
00082 m_pString = 0;
00083 }
00084 }
00085
00086 inline
00087 ~String()
00088 {
00089 if( m_pStringFactory )
00090 {
00091 m_pStringFactory->FreeString( m_pString );
00092 }
00093 }
00094
00095
00096 inline
00097 void Set( const char * i_pString, IStringFactory & i_rStringFactory )
00098 {
00099 m_pString = i_rStringFactory.AllocAndCopyString( i_pString );
00100 m_pStringFactory = &i_rStringFactory;
00101 m_pConstString = 0;
00102 }
00103
00104 inline
00105 operator std::string() const
00106 {
00107 if( m_pStringFactory )
00108 {
00109 return std::string( m_pString );
00110 }
00111 else
00112 {
00113 return std::string( m_pConstString );
00114 }
00115 }
00116
00117 private:
00118 char * m_pString;
00119 const char * m_pConstString;
00120 IStringFactory * m_pStringFactory;
00121 };
00122
00123
00124 inline std::ostream & operator<<( std::ostream & io_rStream, const String & i_rString )
00125 {
00126 io_rStream << std::string( i_rString );
00127 return io_rStream;
00128 }
00129
00130 namespace Direction
00131 {
00132 enum Enum
00133 {
00134 Up,
00135 Down,
00136 Left,
00137 Right,
00138 Forward,
00139 Backward
00140 };
00141 }
00142
00143 namespace StreamMode
00144 {
00145 enum Enum
00146 {
00147 ClientPull,
00148 ClientPullPreFetch,
00149 ServerPush
00150 };
00151 }
00152
00153 namespace TimecodeStandard
00154 {
00155 enum Enum
00156 {
00157 None,
00158 PAL,
00159 NTSC,
00160 NTSCDrop,
00161 Film
00162 };
00163 }
00164
00165 namespace DeviceType
00166 {
00167 enum Enum
00168 {
00169 Unknown,
00170 ForcePlate,
00171 EyeTracker
00172 };
00173 }
00174
00175 namespace Unit
00176 {
00177 enum Enum
00178 {
00179 Unknown,
00180 Volt,
00181 Newton,
00182 NewtonMeter,
00183 Meter,
00184 Kilogram,
00185 Second,
00186 Ampere,
00187 Kelvin,
00188 Mole,
00189 Candela,
00190 Radian,
00191 Steradian,
00192 MeterSquared,
00193 MeterCubed,
00194 MeterPerSecond,
00195 MeterPerSecondSquared,
00196 RadianPerSecond,
00197 RadianPerSecondSquared,
00198 Hertz,
00199 Joule,
00200 Watt,
00201 Pascal,
00202 Lumen,
00203 Lux,
00204 Coulomb,
00205 Ohm,
00206 Farad,
00207 Weber,
00208 Tesla,
00209 Henry,
00210 Siemens,
00211 Becquerel,
00212 Gray,
00213 Sievert,
00214 Katal
00215 };
00216
00217 }
00218
00219 namespace Result
00220 {
00221 enum Enum
00222 {
00223 Unknown,
00224 NotImplemented,
00225 Success,
00226 InvalidHostName,
00227 InvalidMulticastIP,
00228 ClientAlreadyConnected,
00229 ClientConnectionFailed,
00230 ServerAlreadyTransmittingMulticast,
00231 ServerNotTransmittingMulticast,
00232 NotConnected,
00233 NoFrame,
00234 InvalidIndex,
00235 InvalidSubjectName,
00236 InvalidSegmentName,
00237 InvalidMarkerName,
00238 InvalidDeviceName,
00239 InvalidDeviceOutputName,
00240 InvalidLatencySampleName,
00241 CoLinearAxes,
00242 LeftHandedAxes
00243 };
00244 }
00245
00246 class Output_GetVersion
00247 {
00248 public:
00249 unsigned int Major;
00250 unsigned int Minor;
00251 unsigned int Point;
00252 };
00253
00254 class Output_Connect
00255 {
00256 public:
00257 Result::Enum Result;
00258 };
00259
00260 class Output_ConnectToMulticast
00261 {
00262 public:
00263 Result::Enum Result;
00264 };
00265
00266 class Output_Disconnect
00267 {
00268 public:
00269 Result::Enum Result;
00270 };
00271
00272 class Output_IsConnected
00273 {
00274 public:
00275 bool Connected;
00276 };
00277
00278 class Output_StartTransmittingMulticast
00279 {
00280 public:
00281 Result::Enum Result;
00282 };
00283
00284 class Output_StopTransmittingMulticast
00285 {
00286 public:
00287 Result::Enum Result;
00288 };
00289
00290 class Output_EnableSegmentData
00291 {
00292 public:
00293 Result::Enum Result;
00294 };
00295
00296 class Output_EnableMarkerData
00297 {
00298 public:
00299 Result::Enum Result;
00300 };
00301
00302 class Output_EnableUnlabeledMarkerData
00303 {
00304 public:
00305 Result::Enum Result;
00306 };
00307
00308 class Output_EnableDeviceData
00309 {
00310 public:
00311 Result::Enum Result;
00312 };
00313
00314 class Output_DisableSegmentData
00315 {
00316 public:
00317 Result::Enum Result;
00318 };
00319
00320 class Output_DisableMarkerData
00321 {
00322 public:
00323 Result::Enum Result;
00324 };
00325
00326 class Output_DisableUnlabeledMarkerData
00327 {
00328 public:
00329 Result::Enum Result;
00330 };
00331
00332 class Output_DisableDeviceData
00333 {
00334 public:
00335 Result::Enum Result;
00336 };
00337
00338 class Output_IsSegmentDataEnabled
00339 {
00340 public:
00341 bool Enabled;
00342 };
00343
00344 class Output_IsMarkerDataEnabled
00345 {
00346 public:
00347 bool Enabled;
00348 };
00349
00350 class Output_IsUnlabeledMarkerDataEnabled
00351 {
00352 public:
00353 bool Enabled;
00354 };
00355
00356 class Output_IsDeviceDataEnabled
00357 {
00358 public:
00359 bool Enabled;
00360 };
00361
00362 class Output_SetStreamMode
00363 {
00364 public:
00365 Result::Enum Result;
00366 };
00367
00368 class Output_SetAxisMapping
00369 {
00370 public:
00371 Result::Enum Result;
00372 };
00373
00374 class Output_GetAxisMapping
00375 {
00376 public:
00377 Direction::Enum XAxis;
00378 Direction::Enum YAxis;
00379 Direction::Enum ZAxis;
00380 };
00381
00382 class Output_GetFrame
00383 {
00384 public:
00385 Result::Enum Result;
00386 };
00387
00388 class Output_GetFrameNumber
00389 {
00390 public:
00391 Result::Enum Result;
00392 unsigned int FrameNumber;
00393 };
00394
00395 class Output_GetTimecode
00396 {
00397 public:
00398 Result::Enum Result;
00399 unsigned int Hours;
00400 unsigned int Minutes;
00401 unsigned int Seconds;
00402 unsigned int Frames;
00403 unsigned int SubFrame;
00404 bool FieldFlag;
00405 TimecodeStandard::Enum Standard;
00406 unsigned int SubFramesPerFrame;
00407 unsigned int UserBits;
00408 };
00409
00410 class Output_GetFrameRate
00411 {
00412 public:
00413 Result::Enum Result;
00414 double FrameRateHz;
00415 };
00416
00417 class Output_GetLatencySampleCount
00418 {
00419 public:
00420 Result::Enum Result;
00421 unsigned int Count;
00422 };
00423
00424 class Output_GetLatencySampleName
00425 {
00426 public:
00427 Result::Enum Result;
00428 String Name;
00429 };
00430
00431 class Output_GetLatencySampleValue
00432 {
00433 public:
00434 Result::Enum Result;
00435 double Value;
00436 };
00437
00438 class Output_GetLatencyTotal
00439 {
00440 public:
00441 Result::Enum Result;
00442 double Total;
00443 };
00444
00445 class Output_GetSubjectCount
00446 {
00447 public:
00448 Result::Enum Result;
00449 unsigned int SubjectCount;
00450 };
00451
00452 class Output_GetSubjectName
00453 {
00454 public:
00455 Result::Enum Result;
00456 String SubjectName;
00457 };
00458
00459 class Output_GetSubjectRootSegmentName
00460 {
00461 public:
00462 Result::Enum Result;
00463 String SegmentName;
00464 };
00465
00466 class Output_GetSegmentChildCount
00467 {
00468 public:
00469 Result::Enum Result;
00470 unsigned int SegmentCount;
00471 };
00472
00473 class Output_GetSegmentChildName
00474 {
00475 public:
00476 Result::Enum Result;
00477 String SegmentName;
00478 };
00479
00480 class Output_GetSegmentParentName
00481 {
00482 public:
00483 Result::Enum Result;
00484 String SegmentName;
00485 };
00486
00487 class Output_GetSegmentCount
00488 {
00489 public:
00490 Result::Enum Result;
00491 unsigned int SegmentCount;
00492 };
00493
00494 class Output_GetSegmentName
00495 {
00496 public:
00497 Result::Enum Result;
00498 String SegmentName;
00499 };
00500
00501 class Output_GetSegmentStaticTranslation
00502 {
00503 public:
00504 Result::Enum Result;
00505 double Translation[ 3 ];
00506 };
00507
00508 class Output_GetSegmentStaticRotationHelical
00509 {
00510 public:
00511 Result::Enum Result;
00512 double Rotation[ 3 ];
00513 };
00514
00515 class Output_GetSegmentStaticRotationMatrix
00516 {
00517 public:
00518 Result::Enum Result;
00519 double Rotation[ 9 ];
00520 };
00521
00522 class Output_GetSegmentStaticRotationQuaternion
00523 {
00524 public:
00525 Result::Enum Result;
00526 double Rotation[ 4 ];
00527 };
00528
00529 class Output_GetSegmentStaticRotationEulerXYZ
00530 {
00531 public:
00532 Result::Enum Result;
00533 double Rotation[ 3 ];
00534 };
00535
00536 class Output_GetSegmentGlobalTranslation
00537 {
00538 public:
00539 Result::Enum Result;
00540 double Translation[ 3 ];
00541 bool Occluded;
00542 };
00543
00544 class Output_GetSegmentGlobalRotationHelical
00545 {
00546 public:
00547 Result::Enum Result;
00548 double Rotation[ 3 ];
00549 bool Occluded;
00550 };
00551
00552 class Output_GetSegmentGlobalRotationMatrix
00553 {
00554 public:
00555 Result::Enum Result;
00556 double Rotation[ 9 ];
00557 bool Occluded;
00558 };
00559
00560 class Output_GetSegmentGlobalRotationQuaternion
00561 {
00562 public:
00563 Result::Enum Result;
00564 double Rotation[ 4 ];
00565 bool Occluded;
00566 };
00567
00568 class Output_GetSegmentGlobalRotationEulerXYZ
00569 {
00570 public:
00571 Result::Enum Result;
00572 double Rotation[ 3 ];
00573 bool Occluded;
00574 };
00575
00576 class Output_GetSegmentLocalTranslation
00577 {
00578 public:
00579 Result::Enum Result;
00580 double Translation[ 3 ];
00581 bool Occluded;
00582 };
00583
00584 class Output_GetSegmentLocalRotationHelical
00585 {
00586 public:
00587 Result::Enum Result;
00588 double Rotation[ 3 ];
00589 bool Occluded;
00590 };
00591
00592 class Output_GetSegmentLocalRotationMatrix
00593 {
00594 public:
00595 Result::Enum Result;
00596 double Rotation[ 9 ];
00597 bool Occluded;
00598 };
00599
00600 class Output_GetSegmentLocalRotationQuaternion
00601 {
00602 public:
00603 Result::Enum Result;
00604 double Rotation[ 4 ];
00605 bool Occluded;
00606 };
00607
00608 class Output_GetSegmentLocalRotationEulerXYZ
00609 {
00610 public:
00611 Result::Enum Result;
00612 double Rotation[ 3 ];
00613 bool Occluded;
00614 };
00615
00616 class Output_GetMarkerCount
00617 {
00618 public:
00619 Result::Enum Result;
00620 unsigned int MarkerCount;
00621 };
00622
00623 class Output_GetMarkerName
00624 {
00625 public:
00626 Result::Enum Result;
00627 String MarkerName;
00628 };
00629
00630 class Output_GetMarkerParentName
00631 {
00632 public:
00633 Result::Enum Result;
00634 String SegmentName;
00635 };
00636
00637 class Output_GetMarkerGlobalTranslation
00638 {
00639 public:
00640 Result::Enum Result;
00641 double Translation[ 3 ];
00642 bool Occluded;
00643 };
00644
00645 class Output_GetUnlabeledMarkerCount
00646 {
00647 public:
00648 Result::Enum Result;
00649 unsigned int MarkerCount;
00650 };
00651
00652 class Output_GetUnlabeledMarkerGlobalTranslation
00653 {
00654 public:
00655 Result::Enum Result;
00656 double Translation[ 3 ];
00657 };
00658
00659 class Output_GetDeviceCount
00660 {
00661 public:
00662 Result::Enum Result;
00663 unsigned int DeviceCount;
00664 };
00665
00666 class Output_GetDeviceName
00667 {
00668 public:
00669 Result::Enum Result;
00670 String DeviceName;
00671 DeviceType::Enum DeviceType;
00672 };
00673
00674 class Output_GetDeviceOutputCount
00675 {
00676 public:
00677 Result::Enum Result;
00678 unsigned int DeviceOutputCount;
00679 };
00680
00681 class Output_GetDeviceOutputName
00682 {
00683 public:
00684 Result::Enum Result;
00685 String DeviceOutputName;
00686 Unit::Enum DeviceOutputUnit;
00687 };
00688
00689 class Output_GetDeviceOutputValue
00690 {
00691 public:
00692 Result::Enum Result;
00693 double Value;
00694 bool Occluded;
00695 };
00696
00697 class Output_GetDeviceOutputSubsamples
00698 {
00699 public:
00700 Result::Enum Result;
00701 unsigned int DeviceOutputSubsamples;
00702 bool Occluded;
00703 };
00704
00705 class Output_GetForcePlateCount
00706 {
00707 public:
00708 Result::Enum Result;
00709 unsigned int ForcePlateCount;
00710 };
00711
00712 class Output_GetGlobalForceVector
00713 {
00714 public:
00715 Result::Enum Result;
00716 double ForceVector[ 3 ];
00717 };
00718
00719 class Output_GetGlobalMomentVector
00720 {
00721 public:
00722 Result::Enum Result;
00723 double MomentVector[ 3 ];
00724 };
00725
00726 class Output_GetGlobalCentreOfPressure
00727 {
00728 public:
00729 Result::Enum Result;
00730 double CentreOfPressure[ 3 ];
00731 };
00732
00733 class Output_GetForcePlateSubsamples
00734 {
00735 public:
00736 Result::Enum Result;
00737 unsigned int ForcePlateSubsamples;
00738 };
00739
00740 class Output_GetEyeTrackerCount
00741 {
00742 public:
00743 Result::Enum Result;
00744 unsigned int EyeTrackerCount;
00745 };
00746
00747 class Output_GetEyeTrackerGlobalPosition
00748 {
00749 public:
00750 Result::Enum Result;
00751 double Position[ 3 ];
00752 bool Occluded;
00753 };
00754
00755 class Output_GetEyeTrackerGlobalGazeVector
00756 {
00757 public:
00758 Result::Enum Result;
00759 double GazeVector[ 3 ];
00760 bool Occluded;
00761 };
00762
00763 class ClientImpl;
00764
00765 class CLASS_DECLSPEC Client
00766 {
00767 public:
00768 Client();
00769 ~Client();
00770
00771 Output_GetVersion GetVersion() const;
00772
00773 Output_Connect Connect( const String & HostName );
00774 Output_ConnectToMulticast ConnectToMulticast( const String & LocalIP, const String & MulticastIP );
00775 Output_Disconnect Disconnect();
00776 Output_IsConnected IsConnected() const;
00777 Output_StartTransmittingMulticast StartTransmittingMulticast( const String & ServerIP,
00778 const String & MulticastIP );
00779
00780 Output_StopTransmittingMulticast StopTransmittingMulticast();
00781
00782 Output_EnableSegmentData EnableSegmentData();
00783 Output_EnableMarkerData EnableMarkerData();
00784 Output_EnableUnlabeledMarkerData EnableUnlabeledMarkerData();
00785 Output_EnableDeviceData EnableDeviceData();
00786
00787 Output_DisableSegmentData DisableSegmentData();
00788 Output_DisableMarkerData DisableMarkerData();
00789 Output_DisableUnlabeledMarkerData DisableUnlabeledMarkerData();
00790 Output_DisableDeviceData DisableDeviceData();
00791
00792 Output_IsSegmentDataEnabled IsSegmentDataEnabled() const;
00793 Output_IsMarkerDataEnabled IsMarkerDataEnabled() const;
00794 Output_IsUnlabeledMarkerDataEnabled IsUnlabeledMarkerDataEnabled() const;
00795 Output_IsDeviceDataEnabled IsDeviceDataEnabled() const;
00796
00797 Output_SetStreamMode SetStreamMode( const StreamMode::Enum Mode );
00798
00799 Output_SetAxisMapping SetAxisMapping( const Direction::Enum XAxis, const Direction::Enum YAxis, const Direction::Enum ZAxis );
00800 Output_GetAxisMapping GetAxisMapping() const;
00801
00802 Output_GetFrame GetFrame();
00803 Output_GetFrameNumber GetFrameNumber() const;
00804
00805 Output_GetTimecode GetTimecode() const;
00806
00807 Output_GetFrameRate GetFrameRate() const;
00808
00809 Output_GetLatencySampleCount GetLatencySampleCount() const;
00810 Output_GetLatencySampleName GetLatencySampleName( const unsigned int LatencySampleIndex ) const;
00811 Output_GetLatencySampleValue GetLatencySampleValue( const String & LatencySampleName ) const;
00812 Output_GetLatencyTotal GetLatencyTotal() const;
00813
00814 Output_GetSubjectCount GetSubjectCount() const;
00815 Output_GetSubjectName GetSubjectName( const unsigned int SubjectIndex ) const;
00816
00817 Output_GetSubjectRootSegmentName GetSubjectRootSegmentName( const String & SubjectName ) const;
00818
00819 Output_GetSegmentCount GetSegmentCount( const String & SubjectName ) const;
00820
00821 Output_GetSegmentName GetSegmentName( const String & SubjectName,
00822 const unsigned int SegmentIndex ) const;
00823
00824 Output_GetSegmentChildCount GetSegmentChildCount( const String & SubjectName,
00825 const String & SegmentName ) const;
00826
00827 Output_GetSegmentChildName GetSegmentChildName( const String & SubjectName,
00828 const String & SegmentName,
00829 const unsigned int SegmentIndex ) const;
00830
00831 Output_GetSegmentParentName GetSegmentParentName( const String & SubjectName,
00832 const String & SegmentName ) const;
00833
00834 Output_GetSegmentStaticTranslation GetSegmentStaticTranslation( const String & SubjectName,
00835 const String & SegmentName ) const;
00836
00837 Output_GetSegmentStaticRotationHelical GetSegmentStaticRotationHelical( const String & SubjectName,
00838 const String & SegmentName ) const;
00839
00840 Output_GetSegmentStaticRotationMatrix GetSegmentStaticRotationMatrix( const String & SubjectName,
00841 const String & SegmentName ) const;
00842
00843 Output_GetSegmentStaticRotationQuaternion GetSegmentStaticRotationQuaternion( const String & SubjectName,
00844 const String & SegmentName ) const;
00845
00846 Output_GetSegmentStaticRotationEulerXYZ GetSegmentStaticRotationEulerXYZ( const String & SubjectName,
00847 const String & SegmentName ) const;
00848
00849 Output_GetSegmentGlobalTranslation GetSegmentGlobalTranslation( const String & SubjectName,
00850 const String & SegmentName ) const;
00851
00852 Output_GetSegmentGlobalRotationHelical GetSegmentGlobalRotationHelical( const String & SubjectName,
00853 const String & SegmentName ) const;
00854
00855 Output_GetSegmentGlobalRotationMatrix GetSegmentGlobalRotationMatrix( const String & SubjectName,
00856 const String & SegmentName ) const;
00857
00858 Output_GetSegmentGlobalRotationQuaternion GetSegmentGlobalRotationQuaternion( const String & SubjectName,
00859 const String & SegmentName ) const;
00860
00861 Output_GetSegmentGlobalRotationEulerXYZ GetSegmentGlobalRotationEulerXYZ( const String & SubjectName,
00862 const String & SegmentName ) const;
00863
00864 Output_GetSegmentLocalTranslation GetSegmentLocalTranslation( const String & SubjectName,
00865 const String & SegmentName ) const;
00866
00867 Output_GetSegmentLocalRotationHelical GetSegmentLocalRotationHelical( const String & SubjectName,
00868 const String & SegmentName ) const;
00869
00870 Output_GetSegmentLocalRotationMatrix GetSegmentLocalRotationMatrix( const String & SubjectName,
00871 const String & SegmentName ) const;
00872
00873 Output_GetSegmentLocalRotationQuaternion GetSegmentLocalRotationQuaternion( const String & SubjectName,
00874 const String & SegmentName ) const;
00875
00876 Output_GetSegmentLocalRotationEulerXYZ GetSegmentLocalRotationEulerXYZ( const String & SubjectName,
00877 const String & SegmentName ) const;
00878
00879 Output_GetMarkerCount GetMarkerCount( const String & SubjectName ) const;
00880
00881 Output_GetMarkerName GetMarkerName( const String & SubjectName,
00882 const unsigned int MarkerIndex ) const;
00883
00884 Output_GetMarkerParentName GetMarkerParentName( const String & SubjectName,
00885 const String & MarkerName ) const;
00886
00887 Output_GetMarkerGlobalTranslation GetMarkerGlobalTranslation( const String & SubjectName,
00888 const String & MarkerName ) const;
00889
00890
00891 Output_GetUnlabeledMarkerCount GetUnlabeledMarkerCount() const;
00892
00893 Output_GetUnlabeledMarkerGlobalTranslation GetUnlabeledMarkerGlobalTranslation( const unsigned int MarkerIndex ) const;
00894
00895 Output_GetDeviceCount GetDeviceCount() const;
00896 Output_GetDeviceName GetDeviceName( const unsigned int DeviceIndex ) const;
00897
00898 Output_GetDeviceOutputCount GetDeviceOutputCount( const String & DeviceName ) const;
00899
00900 Output_GetDeviceOutputName GetDeviceOutputName( const String & DeviceName,
00901 const unsigned int DeviceOutputIndex ) const;
00902
00903 Output_GetDeviceOutputValue GetDeviceOutputValue( const String & DeviceName,
00904 const String & DeviceOutputName ) const;
00905
00906 Output_GetDeviceOutputSubsamples GetDeviceOutputSubsamples( const String & DeviceName,
00907 const String & DeviceOutputName ) const;
00908
00909 Output_GetDeviceOutputValue GetDeviceOutputValue( const String & DeviceName,
00910 const String & DeviceOutputName,
00911 const unsigned int Subsample ) const;
00912
00913 Output_GetForcePlateCount GetForcePlateCount() const;
00914
00915 Output_GetGlobalForceVector GetGlobalForceVector( const unsigned int ForcePlateIndex ) const;
00916 Output_GetGlobalMomentVector GetGlobalMomentVector( const unsigned int ForcePlateIndex ) const;
00917 Output_GetGlobalCentreOfPressure GetGlobalCentreOfPressure( const unsigned int ForcePlateIndex ) const;
00918
00919 Output_GetForcePlateSubsamples GetForcePlateSubsamples( const unsigned int ForcePlateIndex ) const;
00920
00921 Output_GetGlobalForceVector GetGlobalForceVector( const unsigned int ForcePlateIndex, const unsigned int Subsample ) const;
00922 Output_GetGlobalMomentVector GetGlobalMomentVector( const unsigned int ForcePlateIndex, const unsigned int Subsample ) const;
00923 Output_GetGlobalCentreOfPressure GetGlobalCentreOfPressure( const unsigned int ForcePlateIndex, const unsigned int Subsample ) const;
00924
00925
00926
00927 Output_GetEyeTrackerCount GetEyeTrackerCount() const;
00928
00929 Output_GetEyeTrackerGlobalPosition GetEyeTrackerGlobalPosition( const unsigned int EyeTrackerIndex ) const;
00930 Output_GetEyeTrackerGlobalGazeVector GetEyeTrackerGlobalGazeVector( const unsigned int EyeTrackerIndex ) const;
00931
00932
00933
00934 private:
00935 ClientImpl * m_pClientImpl;
00936 };
00937 }
00938 }