sdh.h
Go to the documentation of this file.
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     //----------------------------------------------------------------------
00429     std::vector<double> SetAxisValueVector( std::vector<int> const& axes,
00430                                             std::vector<double> const& values,
00431                                             pSetFunction ll_set,
00432                                             pGetFunction ll_get,
00433                                             cUnitConverter const* uc,
00434                                             std::vector<double> const& min_values,
00435                                             std::vector<double> const& max_values,
00436                                             char const* name )
00437                                             throw (cSDHLibraryException*);
00438 
00439 
00440     //----------------------------------------------------------------------
00461     std::vector<double> GetAxisValueVector( std::vector<int> const& axes,
00462                                             pGetFunction ll_get,
00463                                             cUnitConverter const* uc,
00464                                             char const* name )
00465         throw (cSDHLibraryException*);
00466 
00467     //-----------------------------------------------------------------
00483     std::vector<int> ToIndexVector( int index, std::vector<int>& all_replacement, int maxindex, char const* name )
00484         throw (cSDHLibraryException*);
00485 
00486 
00487     //-----------------------------------------------------------------
00493     pSetFunction GetMotorCurrentModeFunction( eMotorCurrentMode mode )
00494         throw(cSDHLibraryException*);
00495 
00496 
00497     //-----------------------------------------------------------------
00501     std::vector<double> _GetFingerXYZ( int fi, std::vector<double> r_angles )
00502         throw(cSDHLibraryException*);
00503 
00504 
00505     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_internal
00507     //#####################################################################
00508 
00509 
00510 public:
00511     //----------------------------------------------------------------------
00519 
00520     std::vector<int> all_axes;
00521 
00523     std::vector<int> all_real_axes;
00524 
00526     std::vector<int> all_fingers;
00527 
00529     std::vector<int> all_temperature_sensors;
00530 
00531     //  end of sdhlibrary_cpp_sdh_h_index_vectors
00533     //----------------------------------------------------------------------
00534 
00535 
00536     //----------------------------------------------------------------------
00560 
00561     const cUnitConverter* uc_angle;
00562 
00563 
00565     const cUnitConverter* uc_angular_velocity;
00566 
00567 
00569     const cUnitConverter* uc_angular_acceleration;
00570 
00571 
00573     const cUnitConverter* uc_time;
00574 
00575 
00577     const cUnitConverter* uc_temperature;
00578 
00579 
00581     const cUnitConverter* uc_motor_current;
00582 
00583 
00585     const cUnitConverter* uc_position;
00586     //---------------------
00587 
00588     // end of sdhlibrary_cpp_sdh_h_unit_conversion_ptrs
00590     //----------------------------------------------------------------------
00591 
00592 
00593     //-----------------------------------------------------------------
00677     cSDH( bool _use_radians=false, bool _use_fahrenheit=false, int _debug_level=0 );
00678 
00679 
00680     //----------------------------------------------------------------------
00688     virtual ~cSDH();
00689 
00690 
00691     //######################################################################
00699     //----------------------------------------------------------------------
00701     bool IsVirtualAxis( int iAxis )
00702         throw (cSDHLibraryException*);
00703 
00704     //-----------------------------------------------------------------
00722     void UseRadians( void );
00723 
00724 
00725     //-----------------------------------------------------------------
00745     void UseDegrees( void );
00746 
00747 
00748     //-----------------------------------------------------------------
00768     int GetFingerNumberOfAxes( int iFinger )
00769         throw (cSDHLibraryException*);
00770 
00771 
00772     //-----------------------------------------------------------------
00796     int GetFingerAxisIndex( int iFinger, int iFingerAxis )
00797         throw (cSDHLibraryException*);
00798 
00799 
00800     //-----------------------------------------------------------------
00815     static char const* GetLibraryRelease( void );
00816 
00817 
00818     //-----------------------------------------------------------------
00833     static char const* GetLibraryName( void );
00834 
00835 
00836     //-----------------------------------------------------------------
00854     char const* GetFirmwareRelease( void )
00855         throw (cSDHLibraryException*);
00856 
00857     //-----------------------------------------------------------------
00873     static char const* GetFirmwareReleaseRecommended( void );
00874 
00875     //-----------------------------------------------------------------
00905     bool CheckFirmwareRelease( void )
00906         throw (cSDHLibraryException*);
00907 
00908     //-----------------------------------------------------------------
00937     char const* GetInfo( char const* what )
00938         throw (cSDHLibraryException*);
00939 
00940     //-----------------------------------------------------------------
00993     std::vector<double> GetTemperature( std::vector<int> const& sensors )
00994         throw (cSDHLibraryException*);
00995 
00996 
00997     //----------------------------------------------------------------------
01002     double GetTemperature( int iSensor )
01003         throw (cSDHLibraryException*);
01004 
01005 
01006     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_common
01008     //#####################################################################
01009 
01010 
01011     //######################################################################
01019     //-----------------------------------------------------------------
01054     void OpenRS232(  int _port=0, unsigned long _baudrate = 115200, double _timeout=-1, char const* _device_format_string="/dev/ttyS%d" )
01055         throw (cSDHLibraryException*);
01056 
01057 
01085     void OpenCAN_ESD(  int _net=0,  unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 )
01086         throw (cSDHLibraryException*);
01087 
01088 
01117     void OpenCAN_ESD(  tDeviceHandle _ntcan_handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 )
01118         throw (cSDHLibraryException*);
01119 
01120 
01148     void OpenCAN_PEAK( unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42, const char *_device="/dev/pcanusb0" )
01149         throw (cSDHLibraryException*);
01150 
01151 
01180     void OpenCAN_PEAK(  tDeviceHandle _handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 )
01181         throw (cSDHLibraryException*);
01182 
01202     void OpenTCP( char const* _tcp_adr="192.168.1.1", int _tcp_port=23, double _timeout=0.0 )
01203         throw (cSDHLibraryException*);
01204 
01205     //-----------------------------------------------------------------
01236     void Close( bool leave_enabled=false )
01237         throw (cSDHLibraryException*);
01238 
01239     //-----------------------------------------------------------------
01243     virtual bool IsOpen( void )
01244         throw ();
01245 
01246 
01247     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_communication
01249     //#####################################################################
01250 
01251 
01252     //######################################################################
01260     //-----------------------------------------------------------------
01282     void EmergencyStop( void )
01283         throw (cSDHLibraryException*);
01284 
01285 
01286     //-----------------------------------------------------------------
01317     void Stop( void )
01318         throw (cSDHLibraryException*);
01319 
01320 
01321     //-----------------------------------------------------------------
01322     //-----------------------------------------------------------------
01323     // unimplemented from SAH:
01324     // def GetEmergencyStop( int* piBrakeState)
01325 
01326     //-----------------------------------------------------------------
01376     void SetController( cSDHBase::eControllerType controller )
01377         throw( cSDHLibraryException* );
01378 
01379     //-----------------------------------------------------------------
01401     eControllerType GetController( void  )
01402         throw (cSDHLibraryException*);
01403 
01404     //-----------------------------------------------------------------
01425     void SetVelocityProfile( eVelocityProfile velocity_profile )
01426         throw (cSDHLibraryException*);
01427 
01428 
01429     //-----------------------------------------------------------------
01448     eVelocityProfile GetVelocityProfile( void )
01449         throw (cSDHLibraryException*);
01450 
01451 
01452     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_auxilliary
01454     //#####################################################################
01455 
01456 
01457     //######################################################################
01465     //-----------------------------------------------------------------
01538     void SetAxisMotorCurrent( std::vector<int> const& axes, std::vector<double> const& motor_currents, eMotorCurrentMode mode=eMCM_MOVE )
01539         throw (cSDHLibraryException*);
01540 
01541 
01542     //----------------------------------------------------------------------
01549     void SetAxisMotorCurrent( int iAxis, double motor_current, eMotorCurrentMode mode=eMCM_MOVE )
01550         throw (cSDHLibraryException*);
01551 
01552 
01553     //-----------------------------------------------------------------
01605     std::vector<double> GetAxisMotorCurrent( std::vector<int> const& axes, eMotorCurrentMode mode=eMCM_MOVE )
01606         throw (cSDHLibraryException*);
01607 
01608 
01609     //----------------------------------------------------------------------
01614     double GetAxisMotorCurrent( int iAxis, eMotorCurrentMode mode=eMCM_MOVE )
01615         throw (cSDHLibraryException*);
01616 
01617 
01618     //-----------------------------------------------------------------
01681     void SetAxisEnable( std::vector<int> const& axes, std::vector<double> const& states )
01682         throw (cSDHLibraryException*);
01683 
01684 
01685     //----------------------------------------------------------------------
01692     void SetAxisEnable( int iAxis=All, double state=1.0 )
01693         throw (cSDHLibraryException*);
01694 
01695 
01696     //----------------------------------------------------------------------
01701     void SetAxisEnable( std::vector<int> const& axes, std::vector<bool> const& states )
01702         throw (cSDHLibraryException*);
01703 
01704 
01705     //----------------------------------------------------------------------
01712     void SetAxisEnable( int iAxis=All, bool state=true )
01713         throw (cSDHLibraryException*);
01714 
01715 
01716     //-----------------------------------------------------------------
01765     std::vector<double> GetAxisEnable( std::vector<int> const& axes )
01766         throw (cSDHLibraryException*);
01767 
01768 
01769     //----------------------------------------------------------------------
01774     double GetAxisEnable( int iAxis )
01775         throw (cSDHLibraryException*);
01776 
01777 
01778     //----------------------------------------------------------------------
01824     std::vector<eAxisState> GetAxisActualState( std::vector<int> const& axes )
01825         throw (cSDHLibraryException*);
01826 
01827 
01828     //----------------------------------------------------------------------
01833     eAxisState GetAxisActualState( int iAxis )
01834         throw (cSDHLibraryException*);
01835 
01836 
01837     //-----------------------------------------------------------------
01960     void WaitAxis( std::vector<int> const& axes, double timeout = -1.0 )
01961         throw (cSDHLibraryException*);
01962 
01963 
01964 
01965     //----------------------------------------------------------------------
01972     void WaitAxis( int iAxis, double timeout = -1.0 )
01973         throw (cSDHLibraryException*);
01974 
01975 
01976     //----------------------------------------------------------------------
02050     void SetAxisTargetAngle( std::vector<int> const& axes, std::vector<double> const& angles )
02051         throw (cSDHLibraryException*);
02052 
02053 
02054     //----------------------------------------------------------------------
02061     void SetAxisTargetAngle( int iAxis, double angle )
02062         throw (cSDHLibraryException*);
02063 
02064 
02065     //----------------------------------------------------------------------
02130     std::vector<double> SetAxisTargetGetAxisActualAngle( std::vector<int> const& axes, std::vector<double> const& angles )
02131         throw (cSDHLibraryException*);
02132 
02133 
02134     //-----------------------------------------------------------------
02183     std::vector<double> GetAxisTargetAngle( std::vector<int> const& axes )
02184         throw (cSDHLibraryException*);
02185 
02186 
02187     //----------------------------------------------------------------------
02193     double GetAxisTargetAngle( int iAxis )
02194         throw (cSDHLibraryException*);
02195 
02196 
02197     //-----------------------------------------------------------------
02246     std::vector<double> GetAxisActualAngle( std::vector<int> const& axes )
02247         throw (cSDHLibraryException*);
02248 
02249 
02250     //----------------------------------------------------------------------
02256     double GetAxisActualAngle( int iAxis )
02257         throw (cSDHLibraryException*);
02258 
02259 
02260     //-----------------------------------------------------------------
02349     void SetAxisTargetVelocity( std::vector<int> const& axes, std::vector<double> const& velocities )
02350         throw (cSDHLibraryException*);
02351 
02352 
02353     //----------------------------------------------------------------------
02358     void SetAxisTargetVelocity( int iAxis, double velocity )
02359         throw (cSDHLibraryException*);
02360 
02361 
02362     //----------------------------------------------------------------------
02441     std::vector<double> SetAxisTargetGetAxisActualVelocity( std::vector<int> const& axes, std::vector<double> const& velocities )
02442         throw (cSDHLibraryException*);
02443 
02444 
02445     //-----------------------------------------------------------------
02494     std::vector<double> GetAxisTargetVelocity( std::vector<int> const& axes )
02495         throw (cSDHLibraryException*);
02496 
02497 
02498     //----------------------------------------------------------------------
02504     double GetAxisTargetVelocity( int iAxis )
02505         throw (cSDHLibraryException*);
02506 
02507 
02508     //-----------------------------------------------------------------
02557     std::vector<double> GetAxisLimitVelocity( std::vector<int> const& axes )
02558         throw (cSDHLibraryException*);
02559 
02560 
02561     //----------------------------------------------------------------------
02567     double GetAxisLimitVelocity( int iAxis )
02568         throw (cSDHLibraryException*);
02569 
02570 
02571     //-----------------------------------------------------------------
02620     std::vector<double> GetAxisLimitAcceleration( std::vector<int> const& axes )
02621         throw (cSDHLibraryException*);
02622 
02623 
02624     //----------------------------------------------------------------------
02630     double GetAxisLimitAcceleration( int iAxis )
02631         throw (cSDHLibraryException*);
02632 
02633 
02634     //-----------------------------------------------------------------
02679     std::vector<double> GetAxisActualVelocity( std::vector<int>const& axes )
02680         throw (cSDHLibraryException*);
02681 
02682 
02683     //----------------------------------------------------------------------
02689     double GetAxisActualVelocity( int iAxis )
02690         throw (cSDHLibraryException*);
02691 
02692 
02693     //-----------------------------------------------------------------
02750     std::vector<double> GetAxisReferenceVelocity( std::vector<int>const& axes )
02751         throw (cSDHLibraryException*);
02752 
02753 
02754     //----------------------------------------------------------------------
02760     double GetAxisReferenceVelocity( int iAxis )
02761         throw (cSDHLibraryException*);
02762 
02763 
02764     //-----------------------------------------------------------------
02846     void SetAxisTargetAcceleration( std::vector<int>const& axes, std::vector<double>const& accelerations )
02847         throw (cSDHLibraryException*);
02848 
02849 
02850     //----------------------------------------------------------------------
02855     void SetAxisTargetAcceleration( int iAxis, double acceleration )
02856         throw (cSDHLibraryException*);
02857 
02858 
02859     //-----------------------------------------------------------------
02908     std::vector<double> GetAxisTargetAcceleration( std::vector<int>const& axes )
02909         throw (cSDHLibraryException*);
02910 
02911 
02912     //----------------------------------------------------------------------
02918     double GetAxisTargetAcceleration( int iAxis )
02919         throw (cSDHLibraryException*);
02920 
02921 
02922     //-----------------------------------------------------------------
02977     std::vector<double> GetAxisMinAngle( std::vector<int> const& axes )
02978         throw (cSDHLibraryException*);
02979 
02980 
02981     //----------------------------------------------------------------------
02987     double GetAxisMinAngle( int iAxis )
02988         throw (cSDHLibraryException*);
02989 
02990 
02991     //-----------------------------------------------------------------
03046     std::vector<double> GetAxisMaxAngle( std::vector<int> const& axes )
03047         throw (cSDHLibraryException*);
03048 
03049 
03050     //----------------------------------------------------------------------
03056     double GetAxisMaxAngle( int iAxis )
03057         throw (cSDHLibraryException*);
03058 
03059 
03060     //-----------------------------------------------------------------
03120     std::vector<double> GetAxisMaxVelocity( std::vector<int> const& axes )
03121         throw (cSDHLibraryException*);
03122 
03123 
03124     //----------------------------------------------------------------------
03130     double GetAxisMaxVelocity( int iAxis )
03131         throw (cSDHLibraryException*);
03132 
03133 
03134     //-----------------------------------------------------------------
03189     std::vector<double> GetAxisMaxAcceleration( std::vector<int> const& axes )
03190         throw (cSDHLibraryException*);
03191 
03192 
03193     //----------------------------------------------------------------------
03199     double GetAxisMaxAcceleration( int iAxis )
03200         throw (cSDHLibraryException*);
03201 
03202 
03203     //-----------------------------------------------------------------
03314     double MoveAxis( std::vector<int>const& axes, bool sequ=true )
03315         throw (cSDHLibraryException*);
03316 
03317 
03318     //----------------------------------------------------------------------
03323     double MoveAxis( int iAxis, bool sequ=true )
03324         throw (cSDHLibraryException*);
03325 
03326 
03327     // unimplemented from SAH:
03328     // def GetJointAngle( int iFinger,double* pafAngle);
03329     // def GetJointSpeed( int iFinger,double* pafSpeed);
03330     // def GetJointTorque( int iFinger,double* pafTorque);
03331 
03332 
03333     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_axis
03335     //#####################################################################
03336 
03337     //######################################################################
03345     //-----------------------------------------------------------------
03407     void SetFingerEnable( std::vector<int> const& fingers, std::vector<double> const& states )
03408         throw (cSDHLibraryException*);
03409 
03410 
03411     //----------------------------------------------------------------------
03417     void SetFingerEnable( int iFinger, double state=1.0 )
03418         throw (cSDHLibraryException*);
03419 
03420 
03421     //----------------------------------------------------------------------
03427     void SetFingerEnable( std::vector<int> const& fingers, std::vector<bool> const& states )
03428         throw (cSDHLibraryException*);
03429 
03430 
03431     //----------------------------------------------------------------------
03437     void SetFingerEnable( int iFinger, bool state )
03438         throw (cSDHLibraryException*);
03439 
03440 
03441     //-----------------------------------------------------------------
03491     std::vector<double> GetFingerEnable( std::vector<int> const& fingers )
03492         throw (cSDHLibraryException*);
03493 
03494 
03495     //----------------------------------------------------------------------
03501     double GetFingerEnable( int iFinger )
03502         throw (cSDHLibraryException*);
03503 
03504 
03505     //-----------------------------------------------------------------
03565     void SetFingerTargetAngle( int iFinger, std::vector<double> const& angles )
03566         throw (cSDHLibraryException*);
03567 
03568 
03569     //-----------------------------------------------------------------
03574     void SetFingerTargetAngle( int iFinger, double a0, double a1, double a2 )
03575         throw (cSDHLibraryException*);
03576 
03577 
03578     //-----------------------------------------------------------------
03617     std::vector<double> GetFingerTargetAngle( int iFinger )
03618         throw (cSDHLibraryException*);
03619 
03620 
03621     //-----------------------------------------------------------------
03626     void GetFingerTargetAngle( int iFinger, double& a0, double& a1, double& a2 )
03627         throw (cSDHLibraryException*);
03628 
03629 
03630     //-----------------------------------------------------------------
03669     std::vector<double> GetFingerActualAngle( int iFinger )
03670         throw (cSDHLibraryException*);
03671 
03672 
03673     //-----------------------------------------------------------------
03678     void GetFingerActualAngle( int iFinger, double& a0, double& a1, double& a2 )
03679         throw (cSDHLibraryException*);
03680 
03681 
03682     //-----------------------------------------------------------------
03730     std::vector<double> GetFingerMinAngle( int iFinger )
03731         throw (cSDHLibraryException*);
03732 
03733 
03734     //-----------------------------------------------------------------
03740     void GetFingerMinAngle( int iFinger, double& a0, double& a1, double& a2 )
03741         throw (cSDHLibraryException*);
03742 
03743 
03744     //-----------------------------------------------------------------
03792     std::vector<double> GetFingerMaxAngle( int iFinger )
03793         throw (cSDHLibraryException*);
03794 
03795 
03796     //-----------------------------------------------------------------
03802     void GetFingerMaxAngle( int iFinger, double& a0, double& a1, double& a2 )
03803         throw (cSDHLibraryException*);
03804 
03805 
03806 
03807     //-----------------------------------------------------------------
03864     std::vector<double> GetFingerXYZ( int iFinger, std::vector<double> const& angles )
03865         throw (cSDHLibraryException*);
03866 
03867 
03868     //-----------------------------------------------------------------
03873     std::vector<double> GetFingerXYZ( int iFinger, double a0, double a1, double a2 )
03874         throw (cSDHLibraryException*);
03875 
03876 
03877     //-----------------------------------------------------------------
03975     double MoveFinger( std::vector<int>const& fingers, bool sequ=true )
03976         throw (cSDHLibraryException*);
03977 
03978 
03979     //----------------------------------------------------------------------
03984     double MoveFinger( int iFinger, bool sequ=true )
03985         throw (cSDHLibraryException*);
03986 
03987 
03988     //-----------------------------------------------------------------
04006     double MoveHand( bool sequ=true )
04007         throw (cSDHLibraryException*);
04008 
04009 
04010     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_finger
04012     //#####################################################################
04013 
04014 
04015     //######################################################################
04023     //-----------------------------------------------------------------
04050     double GetGripMaxVelocity( void );
04051 
04052 
04053     //-----------------------------------------------------------------
04123     double GripHand( eGraspId grip, double close, double velocity, bool sequ=true )
04124         throw (cSDHLibraryException*);
04125 
04126 
04127     //  end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_grip
04129     //#####################################################################
04130 
04131 private:
04135     void UpdateSettingsFromSDH();
04136 
04143     void AdjustLimits( cSDHBase::eControllerType controller );
04144 
04145 
04147     std::string release_firmware;
04148 
04150     eControllerType controller_type;
04151 
04152     // unimplemented from SAH:
04153     // def GetFingerTipFT( int iFinger,double* pafFTData);
04154 
04155     // def GetFingerEnableState( int iFinger, int* piEnableState);
04156 
04157     // def GetCommandedValues( int iFinger, double* pafAngle,double* pafVelocity);
04158     // def GetHandConfig( int* piConfig);
04159     // def GetFingerLimitsStatus( int iPort,int iFinger,int* paiLimitStatus);
04160     // def ClearTorqueSensorOffset( int iPort,int iFinger);
04161 
04162     // def SetStiffnessFactor( int iFinger, double* pafStiffnessFactor);
04163 
04164 
04165 
04166 }; // end of class cSDH
04167 //#####################################################################
04168 
04169 NAMESPACE_SDH_END
04170 
04171 #endif
04172 
04173 
04174 //======================================================================
04175 /*
04176   Here are some settings for the emacs/xemacs editor (and can be safely ignored)
04177   (e.g. to explicitely set C++ mode for *.h header files)
04178 
04179   Local Variables:
04180   mode:C++
04181   mode:ELSE
04182   End:
04183 */
04184 //======================================================================]


schunk_sdh
Author(s): Mathias Luedtke , Florian Weisshardt
autogenerated on Thu Aug 27 2015 15:07:03