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 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 };
00172 }
00173
00174 namespace Unit
00175 {
00176 enum Enum
00177 {
00178 Unknown,
00179 Volt,
00180 Newton,
00181 NewtonMeter,
00182 Meter
00183 };
00184 }
00185
00186 namespace Result
00187 {
00188 enum Enum
00189 {
00190 Unknown,
00191 NotImplemented,
00192 Success,
00193 InvalidHostName,
00194 InvalidMulticastIP,
00195 ClientAlreadyConnected,
00196 ClientConnectionFailed,
00197 ServerAlreadyTransmittingMulticast,
00198 ServerNotTransmittingMulticast,
00199 NotConnected,
00200 NoFrame,
00201 InvalidIndex,
00202 InvalidSubjectName,
00203 InvalidSegmentName,
00204 InvalidMarkerName,
00205 InvalidDeviceName,
00206 InvalidDeviceOutputName,
00207 InvalidLatencySampleName,
00208 CoLinearAxes,
00209 LeftHandedAxes
00210 };
00211 }
00212
00213 class Output_GetVersion
00214 {
00215 public:
00216 unsigned int Major;
00217 unsigned int Minor;
00218 unsigned int Point;
00219 };
00220
00221 class Output_Connect
00222 {
00223 public:
00224 Result::Enum Result;
00225 };
00226
00227 class Output_ConnectToMulticast
00228 {
00229 public:
00230 Result::Enum Result;
00231 };
00232
00233 class Output_Disconnect
00234 {
00235 public:
00236 Result::Enum Result;
00237 };
00238
00239 class Output_IsConnected
00240 {
00241 public:
00242 bool Connected;
00243 };
00244
00245 class Output_StartTransmittingMulticast
00246 {
00247 public:
00248 Result::Enum Result;
00249 };
00250
00251 class Output_StopTransmittingMulticast
00252 {
00253 public:
00254 Result::Enum Result;
00255 };
00256
00257 class Output_EnableSegmentData
00258 {
00259 public:
00260 Result::Enum Result;
00261 };
00262
00263 class Output_EnableMarkerData
00264 {
00265 public:
00266 Result::Enum Result;
00267 };
00268
00269 class Output_EnableUnlabeledMarkerData
00270 {
00271 public:
00272 Result::Enum Result;
00273 };
00274
00275 class Output_EnableDeviceData
00276 {
00277 public:
00278 Result::Enum Result;
00279 };
00280
00281 class Output_DisableSegmentData
00282 {
00283 public:
00284 Result::Enum Result;
00285 };
00286
00287 class Output_DisableMarkerData
00288 {
00289 public:
00290 Result::Enum Result;
00291 };
00292
00293 class Output_DisableUnlabeledMarkerData
00294 {
00295 public:
00296 Result::Enum Result;
00297 };
00298
00299 class Output_DisableDeviceData
00300 {
00301 public:
00302 Result::Enum Result;
00303 };
00304
00305 class Output_IsSegmentDataEnabled
00306 {
00307 public:
00308 bool Enabled;
00309 };
00310
00311 class Output_IsMarkerDataEnabled
00312 {
00313 public:
00314 bool Enabled;
00315 };
00316
00317 class Output_IsUnlabeledMarkerDataEnabled
00318 {
00319 public:
00320 bool Enabled;
00321 };
00322
00323 class Output_IsDeviceDataEnabled
00324 {
00325 public:
00326 bool Enabled;
00327 };
00328
00329 class Output_SetStreamMode
00330 {
00331 public:
00332 Result::Enum Result;
00333 };
00334
00335 class Output_SetAxisMapping
00336 {
00337 public:
00338 Result::Enum Result;
00339 };
00340
00341 class Output_GetAxisMapping
00342 {
00343 public:
00344 Direction::Enum XAxis;
00345 Direction::Enum YAxis;
00346 Direction::Enum ZAxis;
00347 };
00348
00349 class Output_GetFrame
00350 {
00351 public:
00352 Result::Enum Result;
00353 };
00354
00355 class Output_GetFrameNumber
00356 {
00357 public:
00358 Result::Enum Result;
00359 unsigned int FrameNumber;
00360 };
00361
00362 class Output_GetTimecode
00363 {
00364 public:
00365 Result::Enum Result;
00366 unsigned int Hours;
00367 unsigned int Minutes;
00368 unsigned int Seconds;
00369 unsigned int Frames;
00370 unsigned int SubFrame;
00371 bool FieldFlag;
00372 TimecodeStandard::Enum Standard;
00373 unsigned int SubFramesPerFrame;
00374 unsigned int UserBits;
00375 };
00376
00377 class Output_GetLatencySampleCount
00378 {
00379 public:
00380 Result::Enum Result;
00381 unsigned int Count;
00382 };
00383
00384 class Output_GetLatencySampleName
00385 {
00386 public:
00387 Result::Enum Result;
00388 String Name;
00389 };
00390
00391 class Output_GetLatencySampleValue
00392 {
00393 public:
00394 Result::Enum Result;
00395 double Value;
00396 };
00397
00398 class Output_GetLatencyTotal
00399 {
00400 public:
00401 Result::Enum Result;
00402 double Total;
00403 };
00404
00405 class Output_GetSubjectCount
00406 {
00407 public:
00408 Result::Enum Result;
00409 unsigned int SubjectCount;
00410 };
00411
00412 class Output_GetSubjectName
00413 {
00414 public:
00415 Result::Enum Result;
00416 String SubjectName;
00417 };
00418
00419 class Output_GetSubjectRootSegmentName
00420 {
00421 public:
00422 Result::Enum Result;
00423 String SegmentName;
00424 };
00425
00426 class Output_GetSegmentChildCount
00427 {
00428 public:
00429 Result::Enum Result;
00430 unsigned int SegmentCount;
00431 };
00432
00433 class Output_GetSegmentChildName
00434 {
00435 public:
00436 Result::Enum Result;
00437 String SegmentName;
00438 };
00439
00440 class Output_GetSegmentParentName
00441 {
00442 public:
00443 Result::Enum Result;
00444 String SegmentName;
00445 };
00446
00447 class Output_GetSegmentCount
00448 {
00449 public:
00450 Result::Enum Result;
00451 unsigned int SegmentCount;
00452 };
00453
00454 class Output_GetSegmentName
00455 {
00456 public:
00457 Result::Enum Result;
00458 String SegmentName;
00459 };
00460
00461 class Output_GetSegmentStaticTranslation
00462 {
00463 public:
00464 Result::Enum Result;
00465 double Translation[ 3 ];
00466 };
00467
00468 class Output_GetSegmentStaticRotationHelical
00469 {
00470 public:
00471 Result::Enum Result;
00472 double Rotation[ 3 ];
00473 };
00474
00475 class Output_GetSegmentStaticRotationMatrix
00476 {
00477 public:
00478 Result::Enum Result;
00479 double Rotation[ 9 ];
00480 };
00481
00482 class Output_GetSegmentStaticRotationQuaternion
00483 {
00484 public:
00485 Result::Enum Result;
00486 double Rotation[ 4 ];
00487 };
00488
00489 class Output_GetSegmentStaticRotationEulerXYZ
00490 {
00491 public:
00492 Result::Enum Result;
00493 double Rotation[ 3 ];
00494 };
00495
00496 class Output_GetSegmentGlobalTranslation
00497 {
00498 public:
00499 Result::Enum Result;
00500 double Translation[ 3 ];
00501 bool Occluded;
00502 };
00503
00504 class Output_GetSegmentGlobalRotationHelical
00505 {
00506 public:
00507 Result::Enum Result;
00508 double Rotation[ 3 ];
00509 bool Occluded;
00510 };
00511
00512 class Output_GetSegmentGlobalRotationMatrix
00513 {
00514 public:
00515 Result::Enum Result;
00516 double Rotation[ 9 ];
00517 bool Occluded;
00518 };
00519
00520 class Output_GetSegmentGlobalRotationQuaternion
00521 {
00522 public:
00523 Result::Enum Result;
00524 double Rotation[ 4 ];
00525 bool Occluded;
00526 };
00527
00528 class Output_GetSegmentGlobalRotationEulerXYZ
00529 {
00530 public:
00531 Result::Enum Result;
00532 double Rotation[ 3 ];
00533 bool Occluded;
00534 };
00535
00536 class Output_GetSegmentLocalTranslation
00537 {
00538 public:
00539 Result::Enum Result;
00540 double Translation[ 3 ];
00541 bool Occluded;
00542 };
00543
00544 class Output_GetSegmentLocalRotationHelical
00545 {
00546 public:
00547 Result::Enum Result;
00548 double Rotation[ 3 ];
00549 bool Occluded;
00550 };
00551
00552 class Output_GetSegmentLocalRotationMatrix
00553 {
00554 public:
00555 Result::Enum Result;
00556 double Rotation[ 9 ];
00557 bool Occluded;
00558 };
00559
00560 class Output_GetSegmentLocalRotationQuaternion
00561 {
00562 public:
00563 Result::Enum Result;
00564 double Rotation[ 4 ];
00565 bool Occluded;
00566 };
00567
00568 class Output_GetSegmentLocalRotationEulerXYZ
00569 {
00570 public:
00571 Result::Enum Result;
00572 double Rotation[ 3 ];
00573 bool Occluded;
00574 };
00575
00576 class Output_GetMarkerCount
00577 {
00578 public:
00579 Result::Enum Result;
00580 unsigned int MarkerCount;
00581 };
00582
00583 class Output_GetMarkerName
00584 {
00585 public:
00586 Result::Enum Result;
00587 String MarkerName;
00588 };
00589
00590 class Output_GetMarkerParentName
00591 {
00592 public:
00593 Result::Enum Result;
00594 String SegmentName;
00595 };
00596
00597 class Output_GetMarkerGlobalTranslation
00598 {
00599 public:
00600 Result::Enum Result;
00601 double Translation[ 3 ];
00602 bool Occluded;
00603 };
00604
00605 class Output_GetUnlabeledMarkerCount
00606 {
00607 public:
00608 Result::Enum Result;
00609 unsigned int MarkerCount;
00610 };
00611
00612 class Output_GetUnlabeledMarkerGlobalTranslation
00613 {
00614 public:
00615 Result::Enum Result;
00616 double Translation[ 3 ];
00617 };
00618
00619 class Output_GetDeviceCount
00620 {
00621 public:
00622 Result::Enum Result;
00623 unsigned int DeviceCount;
00624 };
00625
00626 class Output_GetDeviceName
00627 {
00628 public:
00629 Result::Enum Result;
00630 String DeviceName;
00631 DeviceType::Enum DeviceType;
00632 };
00633
00634 class Output_GetDeviceOutputCount
00635 {
00636 public:
00637 Result::Enum Result;
00638 unsigned int DeviceOutputCount;
00639 };
00640
00641 class Output_GetDeviceOutputName
00642 {
00643 public:
00644 Result::Enum Result;
00645 String DeviceOutputName;
00646 Unit::Enum DeviceOutputUnit;
00647 };
00648
00649 class Output_GetDeviceOutputValue
00650 {
00651 public:
00652 Result::Enum Result;
00653 double Value;
00654 bool Occluded;
00655 };
00656
00657
00658 class ClientImpl;
00659
00660 class CLASS_DECLSPEC Client
00661 {
00662 public:
00663 Client();
00664 ~Client();
00665
00666 Output_GetVersion GetVersion() const;
00667
00668 Output_Connect Connect( const String & HostName );
00669 Output_ConnectToMulticast ConnectToMulticast( const String & HostName, const String & MulticastIP );
00670 Output_Disconnect Disconnect();
00671 Output_IsConnected IsConnected() const;
00672 Output_StartTransmittingMulticast StartTransmittingMulticast( const String & ServerIP,
00673 const String & MulticastIP );
00674
00675 Output_StopTransmittingMulticast StopTransmittingMulticast();
00676
00677 Output_EnableSegmentData EnableSegmentData();
00678 Output_EnableMarkerData EnableMarkerData();
00679 Output_EnableUnlabeledMarkerData EnableUnlabeledMarkerData();
00680 Output_EnableDeviceData EnableDeviceData();
00681
00682 Output_DisableSegmentData DisableSegmentData();
00683 Output_DisableMarkerData DisableMarkerData();
00684 Output_DisableUnlabeledMarkerData DisableUnlabeledMarkerData();
00685 Output_DisableDeviceData DisableDeviceData();
00686
00687 Output_IsSegmentDataEnabled IsSegmentDataEnabled() const;
00688 Output_IsMarkerDataEnabled IsMarkerDataEnabled() const;
00689 Output_IsUnlabeledMarkerDataEnabled IsUnlabeledMarkerDataEnabled() const;
00690 Output_IsDeviceDataEnabled IsDeviceDataEnabled() const;
00691
00692 Output_SetStreamMode SetStreamMode( const StreamMode::Enum Mode );
00693
00694 Output_SetAxisMapping SetAxisMapping( const Direction::Enum XAxis, const Direction::Enum YAxis, const Direction::Enum ZAxis );
00695 Output_GetAxisMapping GetAxisMapping() const;
00696
00697 Output_GetFrame GetFrame();
00698 Output_GetFrameNumber GetFrameNumber() const;
00699
00700 Output_GetTimecode GetTimecode() const;
00701
00702 Output_GetLatencySampleCount GetLatencySampleCount() const;
00703 Output_GetLatencySampleName GetLatencySampleName( const unsigned int LatencySampleIndex ) const;
00704 Output_GetLatencySampleValue GetLatencySampleValue( const String & LatencySampleName ) const;
00705 Output_GetLatencyTotal GetLatencyTotal() const;
00706
00707 Output_GetSubjectCount GetSubjectCount() const;
00708 Output_GetSubjectName GetSubjectName( const unsigned int SubjectIndex ) const;
00709
00710 Output_GetSubjectRootSegmentName GetSubjectRootSegmentName( const String & SubjectName ) const;
00711
00712 Output_GetSegmentCount GetSegmentCount( const String & SubjectName ) const;
00713
00714 Output_GetSegmentName GetSegmentName( const String & SubjectName,
00715 const unsigned int SegmentIndex ) const;
00716
00717 Output_GetSegmentChildCount GetSegmentChildCount( const String & SubjectName,
00718 const String & SegmentName ) const;
00719
00720 Output_GetSegmentChildName GetSegmentChildName( const String & SubjectName,
00721 const String & SegmentName,
00722 const unsigned int SegmentIndex ) const;
00723
00724 Output_GetSegmentParentName GetSegmentParentName( const String & SubjectName,
00725 const String & SegmentName ) const;
00726
00727 Output_GetSegmentStaticTranslation GetSegmentStaticTranslation( const String & SubjectName,
00728 const String & SegmentName ) const;
00729
00730 Output_GetSegmentStaticRotationHelical GetSegmentStaticRotationHelical( const String & SubjectName,
00731 const String & SegmentName ) const;
00732
00733 Output_GetSegmentStaticRotationMatrix GetSegmentStaticRotationMatrix( const String & SubjectName,
00734 const String & SegmentName ) const;
00735
00736 Output_GetSegmentStaticRotationQuaternion GetSegmentStaticRotationQuaternion( const String & SubjectName,
00737 const String & SegmentName ) const;
00738
00739 Output_GetSegmentStaticRotationEulerXYZ GetSegmentStaticRotationEulerXYZ( const String & SubjectName,
00740 const String & SegmentName ) const;
00741
00742 Output_GetSegmentGlobalTranslation GetSegmentGlobalTranslation( const String & SubjectName,
00743 const String & SegmentName ) const;
00744
00745 Output_GetSegmentGlobalRotationHelical GetSegmentGlobalRotationHelical( const String & SubjectName,
00746 const String & SegmentName ) const;
00747
00748 Output_GetSegmentGlobalRotationMatrix GetSegmentGlobalRotationMatrix( const String & SubjectName,
00749 const String & SegmentName ) const;
00750
00751 Output_GetSegmentGlobalRotationQuaternion GetSegmentGlobalRotationQuaternion( const String & SubjectName,
00752 const String & SegmentName ) const;
00753
00754 Output_GetSegmentGlobalRotationEulerXYZ GetSegmentGlobalRotationEulerXYZ( const String & SubjectName,
00755 const String & SegmentName ) const;
00756
00757 Output_GetSegmentLocalTranslation GetSegmentLocalTranslation( const String & SubjectName,
00758 const String & SegmentName ) const;
00759
00760 Output_GetSegmentLocalRotationHelical GetSegmentLocalRotationHelical( const String & SubjectName,
00761 const String & SegmentName ) const;
00762
00763 Output_GetSegmentLocalRotationMatrix GetSegmentLocalRotationMatrix( const String & SubjectName,
00764 const String & SegmentName ) const;
00765
00766 Output_GetSegmentLocalRotationQuaternion GetSegmentLocalRotationQuaternion( const String & SubjectName,
00767 const String & SegmentName ) const;
00768
00769 Output_GetSegmentLocalRotationEulerXYZ GetSegmentLocalRotationEulerXYZ( const String & SubjectName,
00770 const String & SegmentName ) const;
00771
00772 Output_GetMarkerCount GetMarkerCount( const String & SubjectName ) const;
00773
00774 Output_GetMarkerName GetMarkerName( const String & SubjectName,
00775 const unsigned int MarkerIndex ) const;
00776
00777 Output_GetMarkerParentName GetMarkerParentName( const String & SubjectName,
00778 const String & MarkerName ) const;
00779
00780 Output_GetMarkerGlobalTranslation GetMarkerGlobalTranslation( const String & SubjectName,
00781 const String & MarkerName ) const;
00782
00783
00784 Output_GetUnlabeledMarkerCount GetUnlabeledMarkerCount() const;
00785
00786 Output_GetUnlabeledMarkerGlobalTranslation GetUnlabeledMarkerGlobalTranslation( const unsigned int MarkerIndex ) const;
00787
00788 Output_GetDeviceCount GetDeviceCount() const;
00789 Output_GetDeviceName GetDeviceName( const unsigned int DeviceIndex ) const;
00790
00791 Output_GetDeviceOutputCount GetDeviceOutputCount( const String & DeviceName ) const;
00792
00793 Output_GetDeviceOutputName GetDeviceOutputName( const String & DeviceName,
00794 const unsigned int DeviceOutputIndex ) const;
00795
00796 Output_GetDeviceOutputValue GetDeviceOutputValue( const String & DeviceName,
00797 const String & DeviceOutputName ) const;
00798 private:
00799 ClientImpl * m_pClientImpl;
00800 };
00801 }
00802 }