$search
00001 //====================================================================== 00030 //====================================================================== 00031 00032 #ifndef SDH_h_ 00033 #define SDH_h_ 00034 00035 #include "sdhlibrary_settings.h" 00036 00037 #if SDH_USE_VCC 00038 # pragma warning(disable : 4996) 00039 #else 00040 // must be included first on some linuxes 00041 extern "C" { 00042 # include <stdint.h> 00043 } 00044 #endif 00045 00046 #include "basisdef.h" 00047 00048 //---------------------------------------------------------------------- 00049 // System Includes - include with <> 00050 //---------------------------------------------------------------------- 00051 00052 #include <vector> 00053 #include <string> 00054 00055 //---------------------------------------------------------------------- 00056 // Project Includes - include with "" 00057 //---------------------------------------------------------------------- 00058 00059 #include "sdhbase.h" 00060 #include "sdhserial.h" 00061 #include "unit_converter.h" 00062 #include "serialbase.h" 00063 00064 //---------------------------------------------------------------------- 00065 // Defines, enums, unions, structs 00066 //---------------------------------------------------------------------- 00067 00068 #if SDH_USE_NAMESPACE 00069 00076 #endif 00077 00078 NAMESPACE_SDH_START 00079 00080 //---------------------------------------------------------------------- 00081 // Global variables (declarations) 00082 //---------------------------------------------------------------------- 00083 00084 00085 //---------------------------------------------------------------------- 00086 // External functions and classes (declarations) 00087 //---------------------------------------------------------------------- 00088 00089 00090 //---------------------------------------------------------------------- 00091 // Function prototypes (function declarations) 00092 //---------------------------------------------------------------------- 00093 00094 00095 //---------------------------------------------------------------------- 00096 // Class declarations 00097 //---------------------------------------------------------------------- 00098 00099 #if SDH_USE_VCC 00100 // these are needed by VCC for template instantiation into a DLL, 00101 // see http://support.microsoft.com/default.aspx?scid=kb;EN-US;q168958 00102 // and http://www.unknownroad.com/rtfm/VisualStudio/warningC4251.html 00103 // 00104 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<int>; 00105 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<int,std::allocator<int> >; 00106 00107 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<std::vector<int> >; 00108 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<std::vector<int>,std::allocator<std::vector<int> > >; 00109 00110 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<double>; 00111 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<double,std::allocator<double> >; 00112 00113 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<std::vector<double> >; 00114 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<std::vector<double>,std::allocator<std::vector<double> > >; 00115 #endif 00116 00117 //====================================================================== 00118 00172 class VCC_EXPORT cSDH : public cSDHBase 00173 { 00174 public: 00175 00177 enum eMotorCurrentMode 00178 { 00179 eMCM_MOVE=0, 00180 eMCM_GRIP=1, 00181 eMCM_HOLD=2, 00182 00183 eMCM_DIMENSION 00184 }; 00185 00186 00188 enum eAxisState 00189 { 00190 eAS_IDLE = 0, 00191 eAS_POSITIONING, 00192 eAS_SPEED_MODE, 00193 eAS_NOT_INITIALIZED, 00194 eAS_CW_BLOCKED, 00195 eAS_CCW_BLOCKED, 00196 eAS_DISABLED, 00197 eAS_LIMITS_REACHED, 00198 00199 eAS_DIMENSION 00200 }; 00201 00202 00203 //####################################################################### 00219 00220 static cUnitConverter const uc_angle_degrees; 00221 00223 static cUnitConverter const uc_angle_radians; 00224 00226 static cUnitConverter const uc_time_seconds; 00227 00229 static cUnitConverter const uc_time_milliseconds; 00230 00232 static cUnitConverter const uc_temperature_celsius; 00233 00235 static cUnitConverter const uc_temperature_fahrenheit; 00236 00238 static cUnitConverter const uc_angular_velocity_degrees_per_second; 00239 00241 static cUnitConverter const uc_angular_velocity_radians_per_second; 00242 00244 static cUnitConverter const uc_angular_acceleration_degrees_per_second_squared; 00245 00247 static cUnitConverter const uc_angular_acceleration_radians_per_second_squared; 00248 00250 static cUnitConverter const uc_motor_current_ampere; 00251 00253 static cUnitConverter const uc_motor_current_milliampere; 00254 00256 static cUnitConverter const uc_position_millimeter; 00257 00259 static cUnitConverter const uc_position_meter; 00260 00261 00262 // end of doxygen name group sdhlibrary_cpp_sdh_h_unit_conversion_objects 00264 00265 protected: 00266 //--------------------- 00267 // Misc member variables 00268 00270 int NUMBER_OF_AXES_PER_FINGER; 00271 00272 00274 int NUMBER_OF_VIRTUAL_AXES; 00275 00277 int nb_all_axes; 00278 00280 std::vector<int> finger_number_of_axes; 00281 00282 00284 std::vector<std::vector<int> > finger_axis_index; 00285 00287 //f_eps_v; 00288 00290 std::vector<double> f_zeros_v; 00291 00293 std::vector<double> f_ones_v; 00294 00295 00297 std::vector<double> zeros_v; 00298 00300 std::vector<double> ones_v; 00301 00302 00304 std::vector<double> f_min_motor_current_v; 00305 00307 std::vector<double> f_max_motor_current_v; 00308 00309 00310 00312 std::vector<double> f_min_angle_v; 00313 00315 std::vector<double> f_max_angle_v; 00316 00318 std::vector<double> f_min_velocity_v; 00319 00321 std::vector<double> f_max_velocity_v; 00322 00324 std::vector<double> f_min_acceleration_v; 00325 00327 std::vector<double> f_max_acceleration_v; 00328 00330 double grip_max_velocity; 00331 00339 00340 double l1; 00341 00343 double l2; 00344 00345 // distance between center points of base joints f0<->f1, f1<->f2, f0<->f2 00346 double d; 00347 00348 // height of center of base joints above finger base plate 00349 double h; 00350 00355 std::vector<std::vector<double> > offset; 00356 00357 cSerialBase* com; 00358 00359 // !!! make this public for now (to access comm_interface->ref() / comm_interface->pos_save() for hands with missing absolute encoders) 00360 public: 00362 cSDHSerial comm_interface; 00363 00365 virtual void SetDebugOutput( std::ostream* debuglog ) 00366 { 00367 cSDHBase::SetDebugOutput( debuglog ); 00368 comm_interface.SetDebugOutput( debuglog ); 00369 } 00370 00371 protected: 00372 00373 //###################################################################### 00381 //---------------------------------------------------------------------- 00412 std::vector<double> SetAxisValueVector( std::vector<int> const& axes, 00413 std::vector<double> const& values, 00414 pSetFunction ll_set, 00415 pGetFunction ll_get, 00416 cUnitConverter const* uc, 00417 std::vector<double> const& min_values, 00418 std::vector<double> const& max_values, 00419 char const* name ) 00420 throw (cSDHLibraryException*); 00421 00422 00423 //---------------------------------------------------------------------- 00444 std::vector<double> GetAxisValueVector( std::vector<int> const& axes, 00445 pGetFunction ll_get, 00446 cUnitConverter const* uc, 00447 char const* name ) 00448 throw (cSDHLibraryException*); 00449 00450 //----------------------------------------------------------------- 00466 std::vector<int> ToIndexVector( int index, std::vector<int>& all_replacement, int maxindex, char const* name ) 00467 throw (cSDHLibraryException*); 00468 00469 00470 //----------------------------------------------------------------- 00476 pSetFunction GetMotorCurrentModeFunction( eMotorCurrentMode mode ) 00477 throw(cSDHLibraryException*); 00478 00479 00480 //----------------------------------------------------------------- 00484 std::vector<double> _GetFingerXYZ( int fi, std::vector<double> r_angles ) 00485 throw(cSDHLibraryException*); 00486 00487 00488 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_internal 00490 //##################################################################### 00491 00492 00493 public: 00494 //---------------------------------------------------------------------- 00502 00503 std::vector<int> all_axes; 00504 00506 std::vector<int> all_real_axes; 00507 00509 std::vector<int> all_fingers; 00510 00512 std::vector<int> all_temperature_sensors; 00513 00514 // end of sdhlibrary_cpp_sdh_h_index_vectors 00516 //---------------------------------------------------------------------- 00517 00518 00519 //---------------------------------------------------------------------- 00543 00544 const cUnitConverter* uc_angle; 00545 00546 00548 const cUnitConverter* uc_angular_velocity; 00549 00550 00552 const cUnitConverter* uc_angular_acceleration; 00553 00554 00556 const cUnitConverter* uc_time; 00557 00558 00560 const cUnitConverter* uc_temperature; 00561 00562 00564 const cUnitConverter* uc_motor_current; 00565 00566 00568 const cUnitConverter* uc_position; 00569 //--------------------- 00570 00571 // end of sdhlibrary_cpp_sdh_h_unit_conversion_ptrs 00573 //---------------------------------------------------------------------- 00574 00575 00576 //----------------------------------------------------------------- 00660 cSDH( bool _use_radians=false, bool _use_fahrenheit=false, int _debug_level=0 ); 00661 00662 00663 //---------------------------------------------------------------------- 00671 virtual ~cSDH(); 00672 00673 00674 //###################################################################### 00682 //---------------------------------------------------------------------- 00684 bool IsVirtualAxis( int iAxis ) 00685 throw (cSDHLibraryException*); 00686 00687 //----------------------------------------------------------------- 00705 void UseRadians( void ); 00706 00707 00708 //----------------------------------------------------------------- 00728 void UseDegrees( void ); 00729 00730 00731 //----------------------------------------------------------------- 00751 int GetFingerNumberOfAxes( int iFinger ) 00752 throw (cSDHLibraryException*); 00753 00754 00755 //----------------------------------------------------------------- 00779 int GetFingerAxisIndex( int iFinger, int iFingerAxis ) 00780 throw (cSDHLibraryException*); 00781 00782 00783 //----------------------------------------------------------------- 00798 static char const* GetLibraryRelease( void ); 00799 00800 00801 //----------------------------------------------------------------- 00816 static char const* GetLibraryName( void ); 00817 00818 00819 //----------------------------------------------------------------- 00836 char const* GetFirmwareRelease( void ) 00837 throw (cSDHLibraryException*); 00838 00865 char const* GetInfo( char const* what ) 00866 throw (cSDHLibraryException*); 00867 00868 //----------------------------------------------------------------- 00921 std::vector<double> GetTemperature( std::vector<int> const& sensors ) 00922 throw (cSDHLibraryException*); 00923 00924 00925 //---------------------------------------------------------------------- 00930 double GetTemperature( int iSensor ) 00931 throw (cSDHLibraryException*); 00932 00933 00934 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_common 00936 //##################################################################### 00937 00938 00939 //###################################################################### 00947 //----------------------------------------------------------------- 00982 void OpenRS232( int _port=0, unsigned long _baudrate = 115200, double _timeout=-1, char const* _device_format_string="/dev/ttyS%d" ) 00983 throw (cSDHLibraryException*); 00984 00985 01013 void OpenCAN_ESD( int _net=0, unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 ) 01014 throw (cSDHLibraryException*); 01015 01016 01045 void OpenCAN_ESD( tDeviceHandle _ntcan_handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 ) 01046 throw (cSDHLibraryException*); 01047 01048 01076 void OpenCAN_PEAK( unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42, const char *_device="/dev/pcanusb0" ) 01077 throw (cSDHLibraryException*); 01078 01079 01108 void OpenCAN_PEAK( tDeviceHandle _handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 ) 01109 throw (cSDHLibraryException*); 01110 01130 void OpenTCP( char const* _tcp_adr="192.168.1.1", int _tcp_port=23, double _timeout=0.0 ) 01131 throw (cSDHLibraryException*); 01132 01133 //----------------------------------------------------------------- 01164 void Close( bool leave_enabled=false ) 01165 throw (cSDHLibraryException*); 01166 01167 //----------------------------------------------------------------- 01171 virtual bool IsOpen( void ) 01172 throw (); 01173 01174 01175 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_communication 01177 //##################################################################### 01178 01179 01180 //###################################################################### 01188 //----------------------------------------------------------------- 01210 void EmergencyStop( void ) 01211 throw (cSDHLibraryException*); 01212 01213 01214 //----------------------------------------------------------------- 01245 void Stop( void ) 01246 throw (cSDHLibraryException*); 01247 01248 01249 //----------------------------------------------------------------- 01250 //----------------------------------------------------------------- 01251 // unimplemented from SAH: 01252 // def GetEmergencyStop( int* piBrakeState) 01253 01254 //----------------------------------------------------------------- 01304 void SetController( cSDHBase::eControllerType controller ) 01305 throw( cSDHLibraryException* ); 01306 01307 //----------------------------------------------------------------- 01329 eControllerType GetController( void ) 01330 throw (cSDHLibraryException*); 01331 01332 //----------------------------------------------------------------- 01353 void SetVelocityProfile( eVelocityProfile velocity_profile ) 01354 throw (cSDHLibraryException*); 01355 01356 01357 //----------------------------------------------------------------- 01376 eVelocityProfile GetVelocityProfile( void ) 01377 throw (cSDHLibraryException*); 01378 01379 01380 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_auxilliary 01382 //##################################################################### 01383 01384 01385 //###################################################################### 01393 //----------------------------------------------------------------- 01466 void SetAxisMotorCurrent( std::vector<int> const& axes, std::vector<double> const& motor_currents, eMotorCurrentMode mode=eMCM_MOVE ) 01467 throw (cSDHLibraryException*); 01468 01469 01470 //---------------------------------------------------------------------- 01477 void SetAxisMotorCurrent( int iAxis, double motor_current, eMotorCurrentMode mode=eMCM_MOVE ) 01478 throw (cSDHLibraryException*); 01479 01480 01481 //----------------------------------------------------------------- 01533 std::vector<double> GetAxisMotorCurrent( std::vector<int> const& axes, eMotorCurrentMode mode=eMCM_MOVE ) 01534 throw (cSDHLibraryException*); 01535 01536 01537 //---------------------------------------------------------------------- 01542 double GetAxisMotorCurrent( int iAxis, eMotorCurrentMode mode=eMCM_MOVE ) 01543 throw (cSDHLibraryException*); 01544 01545 01546 //----------------------------------------------------------------- 01609 void SetAxisEnable( std::vector<int> const& axes, std::vector<double> const& states ) 01610 throw (cSDHLibraryException*); 01611 01612 01613 //---------------------------------------------------------------------- 01620 void SetAxisEnable( int iAxis=All, double state=1.0 ) 01621 throw (cSDHLibraryException*); 01622 01623 01624 //---------------------------------------------------------------------- 01629 void SetAxisEnable( std::vector<int> const& axes, std::vector<bool> const& states ) 01630 throw (cSDHLibraryException*); 01631 01632 01633 //---------------------------------------------------------------------- 01640 void SetAxisEnable( int iAxis=All, bool state=true ) 01641 throw (cSDHLibraryException*); 01642 01643 01644 //----------------------------------------------------------------- 01693 std::vector<double> GetAxisEnable( std::vector<int> const& axes ) 01694 throw (cSDHLibraryException*); 01695 01696 01697 //---------------------------------------------------------------------- 01702 double GetAxisEnable( int iAxis ) 01703 throw (cSDHLibraryException*); 01704 01705 01706 //---------------------------------------------------------------------- 01752 std::vector<eAxisState> GetAxisActualState( std::vector<int> const& axes ) 01753 throw (cSDHLibraryException*); 01754 01755 01756 //---------------------------------------------------------------------- 01761 eAxisState GetAxisActualState( int iAxis ) 01762 throw (cSDHLibraryException*); 01763 01764 01765 //----------------------------------------------------------------- 01888 void WaitAxis( std::vector<int> const& axes, double timeout = -1.0 ) 01889 throw (cSDHLibraryException*); 01890 01891 01892 01893 //---------------------------------------------------------------------- 01900 void WaitAxis( int iAxis, double timeout = -1.0 ) 01901 throw (cSDHLibraryException*); 01902 01903 01904 //---------------------------------------------------------------------- 01978 void SetAxisTargetAngle( std::vector<int> const& axes, std::vector<double> const& angles ) 01979 throw (cSDHLibraryException*); 01980 01981 01982 //---------------------------------------------------------------------- 01989 void SetAxisTargetAngle( int iAxis, double angle ) 01990 throw (cSDHLibraryException*); 01991 01992 01993 //---------------------------------------------------------------------- 02058 std::vector<double> SetAxisTargetGetAxisActualAngle( std::vector<int> const& axes, std::vector<double> const& angles ) 02059 throw (cSDHLibraryException*); 02060 02061 02062 //----------------------------------------------------------------- 02111 std::vector<double> GetAxisTargetAngle( std::vector<int> const& axes ) 02112 throw (cSDHLibraryException*); 02113 02114 02115 //---------------------------------------------------------------------- 02121 double GetAxisTargetAngle( int iAxis ) 02122 throw (cSDHLibraryException*); 02123 02124 02125 //----------------------------------------------------------------- 02174 std::vector<double> GetAxisActualAngle( std::vector<int> const& axes ) 02175 throw (cSDHLibraryException*); 02176 02177 02178 //---------------------------------------------------------------------- 02184 double GetAxisActualAngle( int iAxis ) 02185 throw (cSDHLibraryException*); 02186 02187 02188 //----------------------------------------------------------------- 02277 void SetAxisTargetVelocity( std::vector<int> const& axes, std::vector<double> const& velocities ) 02278 throw (cSDHLibraryException*); 02279 02280 02281 //---------------------------------------------------------------------- 02286 void SetAxisTargetVelocity( int iAxis, double velocity ) 02287 throw (cSDHLibraryException*); 02288 02289 02290 //---------------------------------------------------------------------- 02369 std::vector<double> SetAxisTargetGetAxisActualVelocity( std::vector<int> const& axes, std::vector<double> const& velocities ) 02370 throw (cSDHLibraryException*); 02371 02372 02373 //----------------------------------------------------------------- 02422 std::vector<double> GetAxisTargetVelocity( std::vector<int> const& axes ) 02423 throw (cSDHLibraryException*); 02424 02425 02426 //---------------------------------------------------------------------- 02432 double GetAxisTargetVelocity( int iAxis ) 02433 throw (cSDHLibraryException*); 02434 02435 02436 //----------------------------------------------------------------- 02485 std::vector<double> GetAxisLimitVelocity( std::vector<int> const& axes ) 02486 throw (cSDHLibraryException*); 02487 02488 02489 //---------------------------------------------------------------------- 02495 double GetAxisLimitVelocity( int iAxis ) 02496 throw (cSDHLibraryException*); 02497 02498 02499 //----------------------------------------------------------------- 02548 std::vector<double> GetAxisLimitAcceleration( std::vector<int> const& axes ) 02549 throw (cSDHLibraryException*); 02550 02551 02552 //---------------------------------------------------------------------- 02558 double GetAxisLimitAcceleration( int iAxis ) 02559 throw (cSDHLibraryException*); 02560 02561 02562 //----------------------------------------------------------------- 02607 std::vector<double> GetAxisActualVelocity( std::vector<int>const& axes ) 02608 throw (cSDHLibraryException*); 02609 02610 02611 //---------------------------------------------------------------------- 02617 double GetAxisActualVelocity( int iAxis ) 02618 throw (cSDHLibraryException*); 02619 02620 02621 //----------------------------------------------------------------- 02678 std::vector<double> GetAxisReferenceVelocity( std::vector<int>const& axes ) 02679 throw (cSDHLibraryException*); 02680 02681 02682 //---------------------------------------------------------------------- 02688 double GetAxisReferenceVelocity( int iAxis ) 02689 throw (cSDHLibraryException*); 02690 02691 02692 //----------------------------------------------------------------- 02774 void SetAxisTargetAcceleration( std::vector<int>const& axes, std::vector<double>const& accelerations ) 02775 throw (cSDHLibraryException*); 02776 02777 02778 //---------------------------------------------------------------------- 02783 void SetAxisTargetAcceleration( int iAxis, double acceleration ) 02784 throw (cSDHLibraryException*); 02785 02786 02787 //----------------------------------------------------------------- 02836 std::vector<double> GetAxisTargetAcceleration( std::vector<int>const& axes ) 02837 throw (cSDHLibraryException*); 02838 02839 02840 //---------------------------------------------------------------------- 02846 double GetAxisTargetAcceleration( int iAxis ) 02847 throw (cSDHLibraryException*); 02848 02849 02850 //----------------------------------------------------------------- 02905 std::vector<double> GetAxisMinAngle( std::vector<int> const& axes ) 02906 throw (cSDHLibraryException*); 02907 02908 02909 //---------------------------------------------------------------------- 02915 double GetAxisMinAngle( int iAxis ) 02916 throw (cSDHLibraryException*); 02917 02918 02919 //----------------------------------------------------------------- 02974 std::vector<double> GetAxisMaxAngle( std::vector<int> const& axes ) 02975 throw (cSDHLibraryException*); 02976 02977 02978 //---------------------------------------------------------------------- 02984 double GetAxisMaxAngle( int iAxis ) 02985 throw (cSDHLibraryException*); 02986 02987 02988 //----------------------------------------------------------------- 03048 std::vector<double> GetAxisMaxVelocity( std::vector<int> const& axes ) 03049 throw (cSDHLibraryException*); 03050 03051 03052 //---------------------------------------------------------------------- 03058 double GetAxisMaxVelocity( int iAxis ) 03059 throw (cSDHLibraryException*); 03060 03061 03062 //----------------------------------------------------------------- 03117 std::vector<double> GetAxisMaxAcceleration( std::vector<int> const& axes ) 03118 throw (cSDHLibraryException*); 03119 03120 03121 //---------------------------------------------------------------------- 03127 double GetAxisMaxAcceleration( int iAxis ) 03128 throw (cSDHLibraryException*); 03129 03130 03131 //----------------------------------------------------------------- 03242 double MoveAxis( std::vector<int>const& axes, bool sequ=true ) 03243 throw (cSDHLibraryException*); 03244 03245 03246 //---------------------------------------------------------------------- 03251 double MoveAxis( int iAxis, bool sequ=true ) 03252 throw (cSDHLibraryException*); 03253 03254 03255 // unimplemented from SAH: 03256 // def GetJointAngle( int iFinger,double* pafAngle); 03257 // def GetJointSpeed( int iFinger,double* pafSpeed); 03258 // def GetJointTorque( int iFinger,double* pafTorque); 03259 03260 03261 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_axis 03263 //##################################################################### 03264 03265 //###################################################################### 03273 //----------------------------------------------------------------- 03335 void SetFingerEnable( std::vector<int> const& fingers, std::vector<double> const& states ) 03336 throw (cSDHLibraryException*); 03337 03338 03339 //---------------------------------------------------------------------- 03345 void SetFingerEnable( int iFinger, double state=1.0 ) 03346 throw (cSDHLibraryException*); 03347 03348 03349 //---------------------------------------------------------------------- 03355 void SetFingerEnable( std::vector<int> const& fingers, std::vector<bool> const& states ) 03356 throw (cSDHLibraryException*); 03357 03358 03359 //---------------------------------------------------------------------- 03365 void SetFingerEnable( int iFinger, bool state ) 03366 throw (cSDHLibraryException*); 03367 03368 03369 //----------------------------------------------------------------- 03419 std::vector<double> GetFingerEnable( std::vector<int> const& fingers ) 03420 throw (cSDHLibraryException*); 03421 03422 03423 //---------------------------------------------------------------------- 03429 double GetFingerEnable( int iFinger ) 03430 throw (cSDHLibraryException*); 03431 03432 03433 //----------------------------------------------------------------- 03493 void SetFingerTargetAngle( int iFinger, std::vector<double> const& angles ) 03494 throw (cSDHLibraryException*); 03495 03496 03497 //----------------------------------------------------------------- 03502 void SetFingerTargetAngle( int iFinger, double a0, double a1, double a2 ) 03503 throw (cSDHLibraryException*); 03504 03505 03506 //----------------------------------------------------------------- 03545 std::vector<double> GetFingerTargetAngle( int iFinger ) 03546 throw (cSDHLibraryException*); 03547 03548 03549 //----------------------------------------------------------------- 03554 void GetFingerTargetAngle( int iFinger, double& a0, double& a1, double& a2 ) 03555 throw (cSDHLibraryException*); 03556 03557 03558 //----------------------------------------------------------------- 03597 std::vector<double> GetFingerActualAngle( int iFinger ) 03598 throw (cSDHLibraryException*); 03599 03600 03601 //----------------------------------------------------------------- 03606 void GetFingerActualAngle( int iFinger, double& a0, double& a1, double& a2 ) 03607 throw (cSDHLibraryException*); 03608 03609 03610 //----------------------------------------------------------------- 03658 std::vector<double> GetFingerMinAngle( int iFinger ) 03659 throw (cSDHLibraryException*); 03660 03661 03662 //----------------------------------------------------------------- 03668 void GetFingerMinAngle( int iFinger, double& a0, double& a1, double& a2 ) 03669 throw (cSDHLibraryException*); 03670 03671 03672 //----------------------------------------------------------------- 03720 std::vector<double> GetFingerMaxAngle( int iFinger ) 03721 throw (cSDHLibraryException*); 03722 03723 03724 //----------------------------------------------------------------- 03730 void GetFingerMaxAngle( int iFinger, double& a0, double& a1, double& a2 ) 03731 throw (cSDHLibraryException*); 03732 03733 03734 03735 //----------------------------------------------------------------- 03792 std::vector<double> GetFingerXYZ( int iFinger, std::vector<double> const& angles ) 03793 throw (cSDHLibraryException*); 03794 03795 03796 //----------------------------------------------------------------- 03801 std::vector<double> GetFingerXYZ( int iFinger, double a0, double a1, double a2 ) 03802 throw (cSDHLibraryException*); 03803 03804 03805 //----------------------------------------------------------------- 03903 double MoveFinger( std::vector<int>const& fingers, bool sequ=true ) 03904 throw (cSDHLibraryException*); 03905 03906 03907 //---------------------------------------------------------------------- 03912 double MoveFinger( int iFinger, bool sequ=true ) 03913 throw (cSDHLibraryException*); 03914 03915 03916 //----------------------------------------------------------------- 03934 double MoveHand( bool sequ=true ) 03935 throw (cSDHLibraryException*); 03936 03937 03938 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_finger 03940 //##################################################################### 03941 03942 03943 //###################################################################### 03951 //----------------------------------------------------------------- 03978 double GetGripMaxVelocity( void ); 03979 03980 03981 //----------------------------------------------------------------- 04051 double GripHand( eGraspId grip, double close, double velocity, bool sequ=true ) 04052 throw (cSDHLibraryException*); 04053 04054 04055 // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_grip 04057 //##################################################################### 04058 04059 private: 04063 void UpdateSettingsFromSDH(); 04064 04071 void AdjustLimits( cSDHBase::eControllerType controller ); 04072 04073 04075 std::string release_firmware; 04076 04078 eControllerType controller_type; 04079 04080 // unimplemented from SAH: 04081 // def GetFingerTipFT( int iFinger,double* pafFTData); 04082 04083 // def GetFingerEnableState( int iFinger, int* piEnableState); 04084 04085 // def GetCommandedValues( int iFinger, double* pafAngle,double* pafVelocity); 04086 // def GetHandConfig( int* piConfig); 04087 // def GetFingerLimitsStatus( int iPort,int iFinger,int* paiLimitStatus); 04088 // def ClearTorqueSensorOffset( int iPort,int iFinger); 04089 04090 // def SetStiffnessFactor( int iFinger, double* pafStiffnessFactor); 04091 04092 04093 04094 }; // end of class cSDH 04095 //##################################################################### 04096 04097 NAMESPACE_SDH_END 04098 04099 #endif 04100 04101 04102 //====================================================================== 04103 /* 04104 Here are some settings for the emacs/xemacs editor (and can be safely ignored) 04105 (e.g. to explicitely set C++ mode for *.h header files) 04106 04107 Local Variables: 04108 mode:C++ 04109 mode:ELSE 04110 End: 04111 */ 04112 //======================================================================]