sdh.h
Go to the documentation of this file.
1 //======================================================================
30 //======================================================================
31 
32 #ifndef SDH_h_
33 #define SDH_h_
34 
35 #include "sdhlibrary_settings.h"
36 
37 #if SDH_USE_VCC
38 # pragma warning(disable : 4996)
39 #else
40 // must be included first on some linuxes
41 extern "C" {
42 # include <stdint.h>
43 }
44 #endif
45 
46 #include "basisdef.h"
47 
48  //----------------------------------------------------------------------
49 // System Includes - include with <>
50 //----------------------------------------------------------------------
51 
52 #include <vector>
53 #include <string>
54 
55 //----------------------------------------------------------------------
56 // Project Includes - include with ""
57 //----------------------------------------------------------------------
58 
59 #include "sdhbase.h"
60 #include "sdhserial.h"
61 #include "unit_converter.h"
62 #include "serialbase.h"
63 
64 //----------------------------------------------------------------------
65 // Defines, enums, unions, structs
66 //----------------------------------------------------------------------
67 
68 #if SDH_USE_NAMESPACE
69 
76 #endif
77 
79 
80 //----------------------------------------------------------------------
81 // Global variables (declarations)
82 //----------------------------------------------------------------------
83 
84 
85 //----------------------------------------------------------------------
86 // External functions and classes (declarations)
87 //----------------------------------------------------------------------
88 
89 
90 //----------------------------------------------------------------------
91 // Function prototypes (function declarations)
92 //----------------------------------------------------------------------
93 
94 
95 //----------------------------------------------------------------------
96 // Class declarations
97 //----------------------------------------------------------------------
98 
99 #if SDH_USE_VCC
100 // these are needed by VCC for template instantiation into a DLL,
101 // see http://support.microsoft.com/default.aspx?scid=kb;EN-US;q168958
102 // and http://www.unknownroad.com/rtfm/VisualStudio/warningC4251.html
103 //
104 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<int>;
105 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<int,std::allocator<int> >;
106 
107 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<std::vector<int> >;
108 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<std::vector<int>,std::allocator<std::vector<int> > >;
109 
110 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<double>;
111 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<double,std::allocator<double> >;
112 
113 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::allocator<std::vector<double> >;
114 VCC_EXPORT_TEMPLATE template class VCC_EXPORT std::vector<std::vector<double>,std::allocator<std::vector<double> > >;
115 #endif
116 
117 //======================================================================
118 
172 class VCC_EXPORT cSDH : public cSDHBase
173 {
174 public:
175 
178  {
179  eMCM_MOVE=0,
180  eMCM_GRIP=1,
181  eMCM_HOLD=2,
182 
183  eMCM_DIMENSION
184  };
185 
186 
189  {
190  eAS_IDLE = 0,
198 
199  eAS_DIMENSION
200  };
201 
202 
203  //#######################################################################
219  static cUnitConverter const uc_angle_degrees;
221 
224 
227 
230 
233 
236 
239 
242 
245 
248 
251 
254 
257 
260 
261 
262  // end of doxygen name group sdhlibrary_cpp_sdh_h_unit_conversion_objects
264 
265 protected:
266  //---------------------
267  // Misc member variables
268 
271 
272 
275 
278 
280  std::vector<int> finger_number_of_axes;
281 
282 
284  std::vector<std::vector<int> > finger_axis_index;
285 
287  //f_eps_v;
288 
290  std::vector<double> f_zeros_v;
291 
293  std::vector<double> f_ones_v;
294 
295 
297  std::vector<double> zeros_v;
298 
300  std::vector<double> ones_v;
301 
302 
304  std::vector<double> f_min_motor_current_v;
305 
307  std::vector<double> f_max_motor_current_v;
308 
309 
310 
312  std::vector<double> f_min_angle_v;
313 
315  std::vector<double> f_max_angle_v;
316 
318  std::vector<double> f_min_velocity_v;
319 
321  std::vector<double> f_max_velocity_v;
322 
324  std::vector<double> f_min_acceleration_v;
325 
327  std::vector<double> f_max_acceleration_v;
328 
331 
339  double l1;
341 
343  double l2;
344 
345  // distance between center points of base joints f0<->f1, f1<->f2, f0<->f2
346  double d;
347 
348  // height of center of base joints above finger base plate
349  double h;
350 
355  std::vector<std::vector<double> > offset;
356 
358 
359  // !!! make this public for now (to access comm_interface->ref() / comm_interface->pos_save() for hands with missing absolute encoders)
360 public:
363 
365  virtual void SetDebugOutput( std::ostream* debuglog )
366  {
367  cSDHBase::SetDebugOutput( debuglog );
368  comm_interface.SetDebugOutput( debuglog );
369  }
370 
371 protected:
372 
373  //######################################################################
381  //----------------------------------------------------------------------
431  std::vector<double> SetAxisValueVector( std::vector<int> const& axes,
432  std::vector<double> const& values,
433  pSetFunction ll_set,
434  pGetFunction ll_get,
435  cUnitConverter const* uc,
436  std::vector<double> const& min_values,
437  std::vector<double> const& max_values,
438  char const* name );
439 
440 
441  //----------------------------------------------------------------------
462  std::vector<double> GetAxisValueVector( std::vector<int> const& axes,
463  pGetFunction ll_get,
464  cUnitConverter const* uc,
465  char const* name );
466 
467  //-----------------------------------------------------------------
483  std::vector<int> ToIndexVector( int index, std::vector<int>& all_replacement, int maxindex, char const* name );
484 
485 
486  //-----------------------------------------------------------------
492  pSetFunction GetMotorCurrentModeFunction( eMotorCurrentMode mode );
493 
494 
495  //-----------------------------------------------------------------
499  std::vector<double> _GetFingerXYZ( int fi, std::vector<double> r_angles );
500 
501 
502  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_internal
504  //#####################################################################
505 
506 
507 public:
508  //----------------------------------------------------------------------
516  std::vector<int> all_axes;
518 
520  std::vector<int> all_real_axes;
521 
523  std::vector<int> all_fingers;
524 
526  std::vector<int> all_temperature_sensors;
527 
528  // end of sdhlibrary_cpp_sdh_h_index_vectors
530  //----------------------------------------------------------------------
531 
532 
533  //----------------------------------------------------------------------
557  const cUnitConverter* uc_angle;
559 
560 
563 
564 
567 
568 
571 
572 
575 
576 
579 
580 
583  //---------------------
584 
585  // end of sdhlibrary_cpp_sdh_h_unit_conversion_ptrs
587  //----------------------------------------------------------------------
588 
589 
590  //-----------------------------------------------------------------
674  cSDH( bool _use_radians=false, bool _use_fahrenheit=false, int _debug_level=0 );
675 
676 
677  //----------------------------------------------------------------------
685  virtual ~cSDH();
686 
687 
688  //######################################################################
696  //----------------------------------------------------------------------
698  bool IsVirtualAxis( int iAxis );
699 
700  //-----------------------------------------------------------------
718  void UseRadians( void );
719 
720 
721  //-----------------------------------------------------------------
741  void UseDegrees( void );
742 
743 
744  //-----------------------------------------------------------------
764  int GetFingerNumberOfAxes( int iFinger );
765 
766 
767  //-----------------------------------------------------------------
791  int GetFingerAxisIndex( int iFinger, int iFingerAxis );
792 
793 
794  //-----------------------------------------------------------------
809  static char const* GetLibraryRelease( void );
810 
811 
812  //-----------------------------------------------------------------
827  static char const* GetLibraryName( void );
828 
829 
830  //-----------------------------------------------------------------
848  char const* GetFirmwareRelease( void );
849 
850  //-----------------------------------------------------------------
866  static char const* GetFirmwareReleaseRecommended( void );
867 
868  //-----------------------------------------------------------------
898  bool CheckFirmwareRelease( void );
899 
900  //-----------------------------------------------------------------
929  char const* GetInfo( char const* what );
930 
931  //-----------------------------------------------------------------
984  std::vector<double> GetTemperature( std::vector<int> const& sensors );
985 
986 
987  //----------------------------------------------------------------------
992  double GetTemperature( int iSensor );
993 
994 
995  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_common
997  //#####################################################################
998 
999 
1000  //######################################################################
1008  //-----------------------------------------------------------------
1043  void OpenRS232( int _port=0, unsigned long _baudrate = 115200, double _timeout=-1, char const* _device_format_string="/dev/ttyS%d" );
1044 
1045 
1073  void OpenCAN_ESD( int _net=0, unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 );
1074 
1075 
1104  void OpenCAN_ESD( tDeviceHandle _ntcan_handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 );
1105 
1106 
1134  void OpenCAN_PEAK( unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42, const char *_device="/dev/pcanusb0" );
1135 
1136 
1165  void OpenCAN_PEAK( tDeviceHandle _handle, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42 );
1166 
1186  void OpenTCP( char const* _tcp_adr="192.168.1.1", int _tcp_port=23, double _timeout=0.0 );
1187 
1188  //-----------------------------------------------------------------
1219  void Close( bool leave_enabled=false );
1220 
1221  //-----------------------------------------------------------------
1225  virtual bool IsOpen( void )
1226  throw ();
1227 
1228 
1229  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_communication
1231  //#####################################################################
1232 
1233 
1234  //######################################################################
1242  //-----------------------------------------------------------------
1264  void EmergencyStop( void );
1265 
1266 
1267  //-----------------------------------------------------------------
1298  void Stop( void );
1299 
1300 
1301  //-----------------------------------------------------------------
1302  //-----------------------------------------------------------------
1303  // unimplemented from SAH:
1304  // def GetEmergencyStop( int* piBrakeState)
1305 
1306  //-----------------------------------------------------------------
1356  void SetController( cSDHBase::eControllerType controller );
1357 
1358  //-----------------------------------------------------------------
1380  eControllerType GetController( void );
1381 
1382  //-----------------------------------------------------------------
1403  void SetVelocityProfile( eVelocityProfile velocity_profile );
1404 
1405 
1406  //-----------------------------------------------------------------
1425  eVelocityProfile GetVelocityProfile( void );
1426 
1427 
1428  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_auxilliary
1430  //#####################################################################
1431 
1432 
1433  //######################################################################
1441  //-----------------------------------------------------------------
1514  void SetAxisMotorCurrent( std::vector<int> const& axes, std::vector<double> const& motor_currents, eMotorCurrentMode mode=eMCM_MOVE );
1515 
1516 
1517  //----------------------------------------------------------------------
1524  void SetAxisMotorCurrent( int iAxis, double motor_current, eMotorCurrentMode mode=eMCM_MOVE );
1525 
1526 
1527  //-----------------------------------------------------------------
1579  std::vector<double> GetAxisMotorCurrent( std::vector<int> const& axes, eMotorCurrentMode mode=eMCM_MOVE );
1580 
1581 
1582  //----------------------------------------------------------------------
1587  double GetAxisMotorCurrent( int iAxis, eMotorCurrentMode mode=eMCM_MOVE );
1588 
1589 
1590  //-----------------------------------------------------------------
1653  void SetAxisEnable( std::vector<int> const& axes, std::vector<double> const& states );
1654 
1655 
1656  //----------------------------------------------------------------------
1663  void SetAxisEnable( int iAxis=All, double state=1.0 );
1664 
1665 
1666  //----------------------------------------------------------------------
1671  void SetAxisEnable( std::vector<int> const& axes, std::vector<bool> const& states );
1672 
1673 
1674  //----------------------------------------------------------------------
1681  void SetAxisEnable( int iAxis=All, bool state=true );
1682 
1683 
1684  //-----------------------------------------------------------------
1733  std::vector<double> GetAxisEnable( std::vector<int> const& axes );
1734 
1735 
1736  //----------------------------------------------------------------------
1741  double GetAxisEnable( int iAxis );
1742 
1743 
1744  //----------------------------------------------------------------------
1790  std::vector<eAxisState> GetAxisActualState( std::vector<int> const& axes );
1791 
1792 
1793  //----------------------------------------------------------------------
1798  eAxisState GetAxisActualState( int iAxis );
1799 
1800 
1801  //-----------------------------------------------------------------
1924  void WaitAxis( std::vector<int> const& axes, double timeout = -1.0 );
1925 
1926 
1927 
1928  //----------------------------------------------------------------------
1935  void WaitAxis( int iAxis, double timeout = -1.0 );
1936 
1937 
1938  //----------------------------------------------------------------------
2012  void SetAxisTargetAngle( std::vector<int> const& axes, std::vector<double> const& angles );
2013 
2014 
2015  //----------------------------------------------------------------------
2022  void SetAxisTargetAngle( int iAxis, double angle );
2023 
2024 
2025  //----------------------------------------------------------------------
2090  std::vector<double> SetAxisTargetGetAxisActualAngle( std::vector<int> const& axes, std::vector<double> const& angles );
2091 
2092 
2093  //-----------------------------------------------------------------
2142  std::vector<double> GetAxisTargetAngle( std::vector<int> const& axes );
2143 
2144 
2145  //----------------------------------------------------------------------
2151  double GetAxisTargetAngle( int iAxis );
2152 
2153 
2154  //-----------------------------------------------------------------
2203  std::vector<double> GetAxisActualAngle( std::vector<int> const& axes );
2204 
2205 
2206  //----------------------------------------------------------------------
2212  double GetAxisActualAngle( int iAxis );
2213 
2214 
2215  //-----------------------------------------------------------------
2304  void SetAxisTargetVelocity( std::vector<int> const& axes, std::vector<double> const& velocities );
2305 
2306 
2307  //----------------------------------------------------------------------
2312  void SetAxisTargetVelocity( int iAxis, double velocity );
2313 
2314 
2315  //----------------------------------------------------------------------
2394  std::vector<double> SetAxisTargetGetAxisActualVelocity( std::vector<int> const& axes, std::vector<double> const& velocities );
2395 
2396 
2397  //-----------------------------------------------------------------
2446  std::vector<double> GetAxisTargetVelocity( std::vector<int> const& axes );
2447 
2448 
2449  //----------------------------------------------------------------------
2455  double GetAxisTargetVelocity( int iAxis );
2456 
2457 
2458  //-----------------------------------------------------------------
2507  std::vector<double> GetAxisLimitVelocity( std::vector<int> const& axes );
2508 
2509 
2510  //----------------------------------------------------------------------
2516  double GetAxisLimitVelocity( int iAxis );
2517 
2518 
2519  //-----------------------------------------------------------------
2568  std::vector<double> GetAxisLimitAcceleration( std::vector<int> const& axes );
2569 
2570 
2571  //----------------------------------------------------------------------
2577  double GetAxisLimitAcceleration( int iAxis );
2578 
2579 
2580  //-----------------------------------------------------------------
2625  std::vector<double> GetAxisActualVelocity( std::vector<int>const& axes );
2626 
2627 
2628  //----------------------------------------------------------------------
2634  double GetAxisActualVelocity( int iAxis );
2635 
2636 
2637  //-----------------------------------------------------------------
2694  std::vector<double> GetAxisReferenceVelocity( std::vector<int>const& axes );
2695 
2696 
2697  //----------------------------------------------------------------------
2703  double GetAxisReferenceVelocity( int iAxis );
2704 
2705 
2706  //-----------------------------------------------------------------
2788  void SetAxisTargetAcceleration( std::vector<int>const& axes, std::vector<double>const& accelerations );
2789 
2790 
2791  //----------------------------------------------------------------------
2796  void SetAxisTargetAcceleration( int iAxis, double acceleration );
2797 
2798 
2799  //-----------------------------------------------------------------
2848  std::vector<double> GetAxisTargetAcceleration( std::vector<int>const& axes );
2849 
2850 
2851  //----------------------------------------------------------------------
2857  double GetAxisTargetAcceleration( int iAxis );
2858 
2859 
2860  //-----------------------------------------------------------------
2915  std::vector<double> GetAxisMinAngle( std::vector<int> const& axes );
2916 
2917 
2918  //----------------------------------------------------------------------
2924  double GetAxisMinAngle( int iAxis );
2925 
2926 
2927  //-----------------------------------------------------------------
2982  std::vector<double> GetAxisMaxAngle( std::vector<int> const& axes );
2983 
2984 
2985  //----------------------------------------------------------------------
2991  double GetAxisMaxAngle( int iAxis );
2992 
2993 
2994  //-----------------------------------------------------------------
3054  std::vector<double> GetAxisMaxVelocity( std::vector<int> const& axes );
3055 
3056 
3057  //----------------------------------------------------------------------
3063  double GetAxisMaxVelocity( int iAxis );
3064 
3065 
3066  //-----------------------------------------------------------------
3121  std::vector<double> GetAxisMaxAcceleration( std::vector<int> const& axes );
3122 
3123 
3124  //----------------------------------------------------------------------
3130  double GetAxisMaxAcceleration( int iAxis );
3131 
3132 
3133  //-----------------------------------------------------------------
3244  double MoveAxis( std::vector<int>const& axes, bool sequ=true );
3245 
3246 
3247  //----------------------------------------------------------------------
3252  double MoveAxis( int iAxis, bool sequ=true );
3253 
3254 
3255  // unimplemented from SAH:
3256  // def GetJointAngle( int iFinger,double* pafAngle);
3257  // def GetJointSpeed( int iFinger,double* pafSpeed);
3258  // def GetJointTorque( int iFinger,double* pafTorque);
3259 
3260 
3261  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_axis
3263  //#####################################################################
3264 
3265  //######################################################################
3273  //-----------------------------------------------------------------
3335  void SetFingerEnable( std::vector<int> const& fingers, std::vector<double> const& states );
3336 
3337 
3338  //----------------------------------------------------------------------
3344  void SetFingerEnable( int iFinger, double state=1.0 );
3345 
3346 
3347  //----------------------------------------------------------------------
3353  void SetFingerEnable( std::vector<int> const& fingers, std::vector<bool> const& states );
3354 
3355 
3356  //----------------------------------------------------------------------
3362  void SetFingerEnable( int iFinger, bool state );
3363 
3364 
3365  //-----------------------------------------------------------------
3415  std::vector<double> GetFingerEnable( std::vector<int> const& fingers );
3416 
3417 
3418  //----------------------------------------------------------------------
3424  double GetFingerEnable( int iFinger );
3425 
3426 
3427  //-----------------------------------------------------------------
3487  void SetFingerTargetAngle( int iFinger, std::vector<double> const& angles );
3488 
3489 
3490  //-----------------------------------------------------------------
3495  void SetFingerTargetAngle( int iFinger, double a0, double a1, double a2 );
3496 
3497 
3498  //-----------------------------------------------------------------
3537  std::vector<double> GetFingerTargetAngle( int iFinger );
3538 
3539 
3540  //-----------------------------------------------------------------
3545  void GetFingerTargetAngle( int iFinger, double& a0, double& a1, double& a2 );
3546 
3547 
3548  //-----------------------------------------------------------------
3587  std::vector<double> GetFingerActualAngle( int iFinger );
3588 
3589 
3590  //-----------------------------------------------------------------
3595  void GetFingerActualAngle( int iFinger, double& a0, double& a1, double& a2 );
3596 
3597 
3598  //-----------------------------------------------------------------
3646  std::vector<double> GetFingerMinAngle( int iFinger );
3647 
3648 
3649  //-----------------------------------------------------------------
3655  void GetFingerMinAngle( int iFinger, double& a0, double& a1, double& a2 );
3656 
3657 
3658  //-----------------------------------------------------------------
3706  std::vector<double> GetFingerMaxAngle( int iFinger );
3707 
3708 
3709  //-----------------------------------------------------------------
3715  void GetFingerMaxAngle( int iFinger, double& a0, double& a1, double& a2 );
3716 
3717 
3718 
3719  //-----------------------------------------------------------------
3776  std::vector<double> GetFingerXYZ( int iFinger, std::vector<double> const& angles );
3777 
3778 
3779  //-----------------------------------------------------------------
3784  std::vector<double> GetFingerXYZ( int iFinger, double a0, double a1, double a2 );
3785 
3786 
3787  //-----------------------------------------------------------------
3885  double MoveFinger( std::vector<int>const& fingers, bool sequ=true );
3886 
3887 
3888  //----------------------------------------------------------------------
3893  double MoveFinger( int iFinger, bool sequ=true );
3894 
3895 
3896  //-----------------------------------------------------------------
3914  double MoveHand( bool sequ=true );
3915 
3916 
3917  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_finger
3919  //#####################################################################
3920 
3921 
3922  //######################################################################
3930  //-----------------------------------------------------------------
3957  double GetGripMaxVelocity( void );
3958 
3959 
3960  //-----------------------------------------------------------------
4030  double GripHand( eGraspId grip, double close, double velocity, bool sequ=true );
4031 
4032 
4033  // end of doxygen name group sdhlibrary_cpp_sdh_h_csdh_grip
4035  //#####################################################################
4036 
4037 private:
4046  void UpdateSettingsFromSDH();
4047 
4054  void AdjustLimits( cSDHBase::eControllerType controller );
4055 
4056 
4058  std::string release_firmware;
4059 
4061  eControllerType controller_type;
4062 
4063  // unimplemented from SAH:
4064  // def GetFingerTipFT( int iFinger,double* pafFTData);
4065 
4066  // def GetFingerEnableState( int iFinger, int* piEnableState);
4067 
4068  // def GetCommandedValues( int iFinger, double* pafAngle,double* pafVelocity);
4069  // def GetHandConfig( int* piConfig);
4070  // def GetFingerLimitsStatus( int iPort,int iFinger,int* paiLimitStatus);
4071  // def ClearTorqueSensorOffset( int iPort,int iFinger);
4072 
4073  // def SetStiffnessFactor( int iFinger, double* pafStiffnessFactor);
4074 
4075 
4076 
4077 }; // end of class cSDH
4078 //#####################################################################
4079 
4081 
4082 #endif
4083 
4084 
4085 //======================================================================
4086 /*
4087  Here are some settings for the emacs/xemacs editor (and can be safely ignored)
4088  (e.g. to explicitely set C++ mode for *.h header files)
4089 
4090  Local Variables:
4091  mode:C++
4092  mode:ELSE
4093  End:
4094 */
4095 //======================================================================]
axis is not initialized or doesn&#39;t exist
Definition: sdh.h:193
eAxisState
The state of an axis (see TPOSCON_STATE in global.h of the SDH firmware)
Definition: sdh.h:188
static cUnitConverter const uc_position_meter
Converter for position: external unit = meter.
Definition: sdh.h:259
#SDH::cSDH is the end user interface class to control a SDH (SCHUNK Dexterous Hand).
Definition: sdh.h:172
Unit conversion class to convert values between physical unit systems.
std::vector< int > all_temperature_sensors
A vector with indices of all temperature sensors.
Definition: sdh.h:526
std::vector< double > ones_v
Vector of nb_all_axes 1.0 values.
Definition: sdh.h:300
The base class to control the SCHUNK Dexterous Hand.
Definition: sdhbase.h:97
axis is blocked is blocked in against counterwise direction
Definition: sdh.h:195
eGraspId
The enum values of the known grasps.
Definition: sdhbase.h:162
static cUnitConverter const uc_motor_current_milliampere
Converter for motor current: external unit = milli Ampere.
Definition: sdh.h:253
int nb_all_axes
The number of all axes including virtual axes.
Definition: sdh.h:277
std::vector< double > f_max_motor_current_v
Maximum allowed motor currents (in internal units (Ampere)), including the virtual axis...
Definition: sdh.h:307
axis is disabled
Definition: sdh.h:196
static cUnitConverter const uc_angular_velocity_degrees_per_second
Default converter for angular velocities (internal unit == external unit): degrees / second...
Definition: sdh.h:238
cSerialBase * com
Definition: sdh.h:357
std::vector< int > finger_number_of_axes
Mapping of finger index to number of real axes of fingers:
Definition: sdh.h:280
virtual bool IsOpen(void)=0
Return true if connection to SDH firmware/hardware is open.
eMotorCurrentMode
the motor current can be set specifically for these modes:
Definition: sdh.h:177
static cUnitConverter const uc_time_milliseconds
Converter for times: external unit = milliseconds.
Definition: sdh.h:229
static cUnitConverter const uc_time_seconds
Default converter for times (internal unit == external unit): seconds.
Definition: sdh.h:226
std::vector< double > zeros_v
Vector of nb_all_axes 0.0 values.
Definition: sdh.h:297
axis is blocked in counterwise direction
Definition: sdh.h:194
std::vector< double > f_max_velocity_v
Maximum allowed axis velocity (in internal units (degrees/second)), including the virtual axis...
Definition: sdh.h:321
int NUMBER_OF_VIRTUAL_AXES
The number of virtual axes.
Definition: sdh.h:274
const cUnitConverter * uc_position
unit converter for position: default = #SDH::cSDH::uc_position_millimeter
Definition: sdh.h:582
The class to communicate with a SDH via RS232.
Definition: sdhserial.h:91
cSimpleVector(cSDHSerial::* pSetFunction)(int, double *)
Type of a pointer to a "set-axis-values" function like cSDHSerial::p, cSDHSerial::pos, ..., cSDHSerial::igrip, cSDHSerial::ihold or cSDHSerial::ilim.
Definition: sdhserial.h:883
eVelocityProfile
An enum for all possible SDH internal velocity profile types.
Definition: sdhbase.h:191
Interface of class #SDH::cUnitConverter.
std::vector< double > f_min_angle_v
Minimum allowed axis angles (in internal units (degrees)), including the virtual axis.
Definition: sdh.h:312
double l2
length of limb 2 (distal joint to fingertip) in mm
Definition: sdh.h:343
const cUnitConverter * uc_angular_acceleration
unit convert for (axis) angular accelerations: default = #SDH::cSDH::uc_angular_acceleration_degrees_...
Definition: sdh.h:566
the goal position has not been reached yet
Definition: sdh.h:191
axis is in speed mode
Definition: sdh.h:192
Low-level communication class to access a serial port.
Definition: serialbase.h:105
#define NAMESPACE_SDH_START
static cUnitConverter const uc_angle_radians
Converter for angles: external unit = radians.
Definition: sdh.h:223
virtual void SetDebugOutput(std::ostream *debuglog)
change the stream to use for debug messages
Definition: sdhbase.h:273
std::vector< double > f_min_acceleration_v
Minimum allowed axis acceleration (in internal units (degrees/(second * second))), including the virtual axis.
Definition: sdh.h:324
const cUnitConverter * uc_time
unit convert for times: default = uc_time_seconds
Definition: sdh.h:570
const cUnitConverter * uc_angular_velocity
unit convert for (axis) angular velocities: default = #SDH::cSDH::uc_angular_velocity_degrees_per_sec...
Definition: sdh.h:562
static cUnitConverter const uc_angular_velocity_radians_per_second
Converter for angular velocieties: external unit = radians/second.
Definition: sdh.h:241
double d
Definition: sdh.h:346
std::vector< double > f_zeros_v
Vector of 3 epsilon values.
Definition: sdh.h:290
static cUnitConverter const uc_position_millimeter
Default converter for position (internal unit == external unit): millimeter.
Definition: sdh.h:256
const cUnitConverter * uc_motor_current
unit converter for motor curent: default = #SDH::cSDH::uc_motor_current_ampere
Definition: sdh.h:578
std::vector< int > all_fingers
A vector with indices of all fingers (in natural order)
Definition: sdh.h:523
eControllerType
An enum for all possible SDH internal controller types (order must match that in the SDH firmware in ...
Definition: sdhbase.h:176
std::vector< int > all_real_axes
A vector with indices of all real axes (in natural order), excluding the virtual axis.
Definition: sdh.h:520
cSDHSerial comm_interface
The object to interface with the SDH attached via serial RS232 or CAN or TCP.
Definition: sdh.h:362
int NUMBER_OF_AXES_PER_FINGER
The number of axis per finger (for finger 1 this includes the "virtual" base axis) ...
Definition: sdh.h:270
static cUnitConverter const uc_temperature_celsius
Default converter for temparatures (internal unit == external unit): degrees celsius.
Definition: sdh.h:232
Interface of class #SDH::cSDHBase.
Interface of class #SDH::cSDHSerial.
std::vector< double > f_max_acceleration_v
Maximum allowed axis acceleration (in internal units (degrees/(second * second))), including the virtual axis.
Definition: sdh.h:327
double grip_max_velocity
Maximum allowed grip velocity (in internal units (degrees/second))
Definition: sdh.h:330
std::vector< std::vector< int > > finger_axis_index
Mapping of finger index, finger axis index to axis index:
Definition: sdh.h:284
std::vector< double > f_max_angle_v
Maximum allowed axis angles (in internal units (degrees)), including the virtual axis.
Definition: sdh.h:315
std::vector< double > f_min_velocity_v
Minimum allowed axis velocity (in internal units (degrees/second)), including the virtual axis...
Definition: sdh.h:318
static cUnitConverter const uc_angular_acceleration_degrees_per_second_squared
Default converter for angular accelerations (internal unit == external unit): degrees / second...
Definition: sdh.h:244
virtual void SetDebugOutput(std::ostream *debuglog)
change the stream to use for debug messages
Definition: sdh.h:365
#define NAMESPACE_SDH_END
This file contains settings to make the SDHLibrary compile on differen systems:
static cUnitConverter const uc_motor_current_ampere
Default converter for motor current (internal unit == external unit): Ampere.
Definition: sdh.h:250
static cUnitConverter const uc_angular_acceleration_radians_per_second_squared
Converter for angular velocieties: external unit = radians/second.
Definition: sdh.h:247
double h
Definition: sdh.h:349
std::vector< double > f_min_motor_current_v
Minimum allowed motor currents (in internal units (Ampere)), including the virtual axis...
Definition: sdh.h:304
std::vector< double > f_ones_v
Vector of 3 1.0 values.
Definition: sdh.h:293
This file contains some basic definitions (defines, macros, datatypes)
Interface of class #SDH::cSerialBase, a virtal base class to access serial communication channels lik...
position limits reached and axis stopped
Definition: sdh.h:197
const cUnitConverter * uc_temperature
unit convert for temperatures: default = #SDH::cSDH::uc_temperature_celsius
Definition: sdh.h:574
std::vector< std::vector< double > > offset
Definition: sdh.h:355
cSimpleVector(cSDHSerial::* pGetFunction)(int, double *)
Type of a pointer to a "get-axis-values" function like cSDHSerial::p, cSDHSerial::pos, ..., cSDHSerial::igrip, cSDHSerial::ihold or cSDHSerial::ilim.
Definition: sdhserial.h:886
int32_t Int32
signed integer, size 4 Byte (32 Bit)
Definition: basisdef.h:64
NAMESPACE_SDH_START typedef void * tDeviceHandle
generic device handle for CAN devices
Definition: serialbase.h:64
static cUnitConverter const uc_temperature_fahrenheit
Converter for temperatures: external unit = degrees fahrenheit.
Definition: sdh.h:235


sdhlibrary_cpp
Author(s): Dirk Osswald
autogenerated on Sun Aug 18 2019 03:42:20