Go to the documentation of this file.
   32 #define _USE_MATH_DEFINES 
  135                                               std::vector<double> 
const& values,
 
  139                                               std::vector<double> 
const& min_values,
 
  140                                               std::vector<double> 
const& max_values,
 
  146     if (axes.size() != values.size())
 
  148         throw new cSDHErrorInvalidParameter( 
cMsg( 
"Lengths of axis indices and %s values vectors do not match (%ld != %ld)", name, axes.size(), values.size()) );
 
  152     std::vector<int>::const_iterator ai = axes.begin();
 
  153     std::vector<double>::const_iterator vi = values.begin();
 
  154     for ( axes.begin(), vi = values.begin();
 
  161         used |= (1 << (*ai));
 
  165     cdbg << 
"SetAxisValueVector: axes and values ok, used=" << used << 
"\n";
 
  174     bool c_value_valid = 
false;
 
  185         c_value_valid = 
true;
 
  188     for ( ai = axes.begin(), vi = values.begin();
 
  202         if (SDH_ISNAN((*vi)))
 
  211                 c_value_valid = 
true;
 
  221         cdbg << 
"SetAxisValueVector: setting v=" << v << 
"\n";
 
  223             all_values[ *ai ] = v;
 
  229     std::vector<double> rv( axes.size(), 0.0 ); 
 
  232     for ( i=0, ai = axes.begin();
 
  241         v = returned_values[ *ai ];
 
  260     std::vector<int>::const_iterator ai;
 
  262     for ( ai = axes.begin();
 
  276     std::vector<double> rv( axes.size(), 0.0 ); 
 
  279     for ( i=0, ai = axes.begin();
 
  288         v = all_values[ *ai ];
 
  298 cSDH::cSDH( 
bool _use_radians, 
bool _use_fahrenheit, 
int _debug_level )
 
  305     comm_interface( _debug_level-1 ),
 
  306     controller_type( eCT_INVALID )
 
  309     cdbg.
PDM( 
"Debug messages of cSDH are printed like this.\n" );
 
  321     if ( _use_fahrenheit )
 
  358     (*f0_axis_index)[0] = 0;
 
  359     (*f0_axis_index)[1] = 1;
 
  360     (*f0_axis_index)[2] = 2;
 
  362     (*f1_axis_index)[0] = 7;
 
  363     (*f1_axis_index)[1] = 3;
 
  364     (*f1_axis_index)[2] = 4;
 
  366     (*f2_axis_index)[0] = 0;
 
  367     (*f2_axis_index)[1] = 5;
 
  368     (*f2_axis_index)[2] = 6;
 
  450     std::vector<double>* f0_offset = 
new std::vector<double>( 3, 0.0 );
 
  451     std::vector<double>* f1_offset = 
new std::vector<double>( 3, 0.0 );
 
  452     std::vector<double>* f2_offset = 
new std::vector<double>( 3, 0.0 );
 
  454     (*f0_offset)[ 0 ] = 
d/2.0;                          
 
  455     (*f0_offset)[ 1 ] = 
d/2.0*tan( 
DegToRad(30.0) );    
 
  456     (*f0_offset)[ 2 ] = 
h;                              
 
  458     (*f1_offset)[ 0 ] =  0.0;                           
 
  459     (*f1_offset)[ 1 ] =  -
d/(2.0*cos( 
DegToRad(30.0) ));
 
  460     (*f1_offset)[ 2 ] =  
h;                             
 
  462     (*f2_offset)[ 0 ] =  -
d/2.0;                        
 
  463     (*f2_offset)[ 1 ] =  
d/2.0*tan( 
DegToRad(30.0) );   
 
  464     (*f2_offset)[ 2 ] =  
h;                             
 
  479         cdbg << 
"Cleanup: Closing port in destructor ~cSDH\n";
 
  492 std::vector<int> 
cSDH::ToIndexVector( 
int index, std::vector<int>& all_replacement, 
int maxindex, 
char const* name )
 
  496         return all_replacement;
 
  501         return std::vector<int>( 1, index );
 
  509     return std::vector<double>( length, *convert( value ) );
 
  529 std::vector<std::vector<double> > cSDH::_GetHandXYZ( 
double angles )
 
  546     std::vector<double> rv(3,0.0);
 
  567     double s_b  = sin( r_angles[1] );
 
  568     double s_bc = sin( r_angles[1] + r_angles[2] );
 
  569     double l1_s_b_l2_s_bc = (
l1*s_b + 
l2*s_bc);
 
  571     rv[0] = fac_x * (l1_s_b_l2_s_bc) * sin( r_angles[0] ) + 
offset[ fi ][0]; 
 
  572     rv[1] = fac_y * (l1_s_b_l2_s_bc) * cos( r_angles[0] ) + 
offset[ fi ][1]; 
 
  573     rv[2] = 
l1*cos( r_angles[1] ) + 
l2*cos( r_angles[1] + r_angles[2] ) + 
offset[ fi][2]; 
 
  663     cdbg << 
"GetInfo: " << what << 
" is requested\n";
 
  665     if ( ! strcmp( what,
"release" ) || ! strcmp( what, 
"release-library" ) )
 
  667     if ( ! strcmp( what, 
"date" ) || ! strcmp( what, 
"date-library" ) )
 
  669     if ( ! strcmp( what, 
"release-firmware-recommended" ) )
 
  675     if ( ! strcmp( what, 
"release-firmware" ) )
 
  677     if ( ! strcmp( what, 
"date-firmware") )
 
  679     if ( ! strcmp( what, 
"release-soc" ) )
 
  681     if ( ! strcmp( what, 
"date-soc" ) )
 
  683     if ( ! strcmp( what, 
"date-soc" ) )
 
  685     if ( ! strcmp( what, 
"id-sdh") )
 
  687     if ( ! strcmp( what, 
"sn-sdh" ) )
 
  699     std::vector<double> rv;
 
  701     for ( std::vector<int>::const_iterator si = sensors.begin();
 
  733 void cSDH::OpenRS232(  
int _port, 
unsigned long _baudrate, 
double _timeout, 
char const* _device_format_string )
 
  743     com = 
new cRS232( _port, _baudrate, _timeout, _device_format_string );
 
  750     cdbg << 
"cSDH.OpenRS232() successfully opened RS232 port.\n";
 
  760     if ( _timeout < 0.0 )
 
  775     cdbg << 
"cSDH.OpenCAN_ESD() successfully opened CAN port.\n";
 
  788     if ( _timeout < 0.0 )
 
  803     cdbg << 
"cSDH.OpenCAN_ESD() successfully opened CAN port.\n";
 
  816     if ( _timeout < 0.0 )
 
  831     cdbg << 
"cSDH.OpenCAN_PEAK() successfully opened PEAK CAN device \"" << _device << 
"\".\n";
 
  844     if ( _timeout < 0.0 )
 
  859     cdbg << 
"cSDH.OpenCAN_PEAK() successfully reopened CAN device.\n";
 
  883     cdbg << 
"cSDH.OpenTCP() successfully opened TCP connection to \"" << _tcp_adr << 
":" << _tcp_port << 
"\"\n";
 
  894             if (! leave_enabled )
 
  896                 cdbg << 
"Switching off power before closing connection to SDH\n";
 
  901             cdbg << 
"Connection to SDH closed.\n";
 
  905             cdbg << 
"Ignoring exception while closing connection to SDH (" << e->
what() << 
")\n";
 
  920     return comm_interface.IsOpen();
 
 1019     std::vector<double> motor_currents( axes.size(), motor_current );
 
 1072     std::vector<double> states( axes.size(), state );
 
 1087     std::vector<double> dstates( states.size(), 0.0 );
 
 1088     std::vector<bool>::const_iterator bi;
 
 1089     std::vector<double>::iterator di;
 
 1090     for ( bi = states.begin(), di = dstates.begin();
 
 1091           bi != states.end() && di != dstates.end();
 
 1113                                "enabled/disabled" );
 
 1133     std::vector<eAxisState> estates;
 
 1134     std::vector<double>::const_iterator si;
 
 1136     for ( si =  fstates.begin();
 
 1137           si != fstates.end();
 
 1140         estates.push_back( 
eAxisState( 
int( *si ) ) );
 
 1175         std::vector<eAxisState>::const_iterator si;
 
 1176         for( si =  states.begin();
 
 1180             finished = finished  &&  (*si != busy );
 
 1183         if (!finished  &&  timeout >= 0.0  &&  start_time.
Elapsed() > timeout )
 
 1187     } 
while ( ! finished );
 
 1194     std::vector<int> axes;
 
 1201         axes.push_back( iAxis );
 
 1226     std::vector<double> angles( axes.size(), angle );
 
 1246                                "set target, get actual angle" );
 
 1296                         "target velocity" );
 
 1306     std::vector<double> velocities( axes.size(), velocity );
 
 1314                         "target velocity" );
 
 1325                                "set target, get actual velocity" );
 
 1334                                "target velocity" );
 
 1353         double all_velocities[] = { 85.7, 200.0, 157.8, 200.0, 157.8, 200.0, 157.8, 85.7 };
 
 1354         std::vector<double> rv;
 
 1355         std::vector<int>::const_iterator ai;
 
 1357         for ( ai = axes.begin();
 
 1380         double all_accelerations[] = { 5000.0, 400.0, 1500.0, 400.0, 1500.0, 400.0, 1500.0, 400.0 };
 
 1381         std::vector<double> rv;
 
 1382         std::vector<int>::const_iterator ai;
 
 1384         for ( ai = axes.begin();
 
 1396                                "acceleration limit" );
 
 1403     std::vector<int> axes( 1, iAxis );
 
 1412     std::vector<int> axes( 1, iAxis );
 
 1424                                "actual velocity" );
 
 1443                                "reference velocity" );
 
 1464                         "target acceleration" );
 
 1474     std::vector<double> accelerations( axes.size(), acceleration );
 
 1482                         "target acceleration" );
 
 1492                                "target acceleration" );
 
 1508     std::vector<double> rv( axes.size(), 0.0 );
 
 1510     std::vector<int>::const_iterator ai;
 
 1511     std::vector<double>::iterator    vi;
 
 1512     for( ai = axes.begin(), vi = rv.begin();
 
 1536     std::vector<double> rv( axes.size(), 0.0 );
 
 1538     std::vector<int>::const_iterator ai;
 
 1539     std::vector<double>::iterator    vi;
 
 1540     for( ai = axes.begin(), vi = rv.begin();
 
 1564     std::vector<double> rv( axes.size(), 0.0 );
 
 1566     std::vector<int>::const_iterator ai;
 
 1567     std::vector<double>::iterator    vi;
 
 1568     for( ai = axes.begin(), vi = rv.begin();
 
 1592     std::vector<double> rv( axes.size(), 0.0 );
 
 1594     std::vector<int>::const_iterator ai;
 
 1595     std::vector<double>::iterator    vi;
 
 1596     for( ai = axes.begin(), vi = rv.begin();
 
 1622     unsigned long nan[2]={0xffffffff, 0x7fffffff};
 
 1623     std::vector<double> all_states( 
NUMBER_OF_AXES, *( 
double* )nan);
 
 1628     std::vector<int>::const_iterator fi;
 
 1629     std::vector<double>::const_iterator vi;
 
 1630     for( fi  = fingers.begin(), vi  = states.begin();
 
 1631          fi != fingers.end() && vi != states.end();
 
 1636         std::vector<int>::const_iterator fai;
 
 1641         if ( *fai == 0  &&  !SDH_ISNAN( all_states[ *fai ] )  && !SDH_ISNAN( *vi ) )
 
 1648             all_states[ *fai ] += *vi;
 
 1650         all_states[ *fai ] = *vi;
 
 1655     if ( !SDH_ISNAN( all_states[ 0 ] ) )
 
 1656         all_states[ 0 ] = 
ToRange( all_states[ 0 ], 0.0, 1.0 );
 
 1665     std::vector<double> dstates( states.size(), 0.0 );
 
 1666     std::vector<bool>::const_iterator bi;
 
 1667     std::vector<double>::iterator di;
 
 1668     for ( bi = states.begin(), di = dstates.begin();
 
 1669           bi != states.end() && di != dstates.end();
 
 1681     std::vector<int> axes;
 
 1683     if ( iFinger == 
All )
 
 1694     std::vector<double> states( axes.size(), state );
 
 1716     std::vector<double> rv;
 
 1721     std::vector<int>::const_iterator fi;
 
 1723     for( fi  = fingers.begin();
 
 1724          fi != fingers.end();
 
 1729         double finger_state = 0.0;
 
 1730         std::vector<int>::const_iterator fai;
 
 1736             finger_state += 1.0; 
 
 1738             finger_state += all_states[ *fai ];
 
 1866     std::vector<double> r_angles;
 
 1888     std::vector<double> a012;
 
 1889     a012.push_back( a0 );
 
 1890     a012.push_back( a1 );
 
 1891     a012.push_back( a2 );
 
 1923     for ( std::vector<int>::const_iterator ai = axes.begin();
 
 1935         a_angles[ *ai ] = t_angles[ *ai ] ;
 
 1962         return MoveAxis( std::vector<int>( 1, iAxis ), sequ );
 
 1992     for ( std::vector<int>::const_iterator fi = fingers.begin();
 
 1993           fi != fingers.end();
 
 2006             a_angles[ *fai ] = t_angles[ *fai ] ;
 
 2034         return MoveFinger( std::vector<int>( 1, iFinger ), sequ );
 
 2055     CheckRange( close, 0.0, 1.0, 
"open/close ratio" );
 
 2077     std::vector<double>::iterator vi;
 
 2133         assert( 
"controller invalid" == 
NULL );
 
  
std::vector< double > f_zeros_v
Vector of 3 epsilon values.
void OpenTCP(char const *_tcp_adr="192.168.1.1", int _tcp_port=23, double _timeout=0.0)
#define FIRMWARE_RELEASE_RECOMMENDED
static const cUnitConverter uc_motor_current_ampere
Default converter for motor current (internal unit == external unit): Ampere.
void SetAxisTargetVelocity(std::vector< int > const &axes, std::vector< double > const &velocities)
std::vector< double > f_min_angle_v
Minimum allowed axis angles (in internal units (degrees)), including the virtual axis.
eControllerType con(eControllerType controller)
int GetFingerNumberOfAxes(int iFinger)
static const cUnitConverter uc_temperature_fahrenheit
Converter for temperatures: external unit = degrees fahrenheit.
#define PROJECT_DATE
Date of the release of the software project.
cSimpleVector rvel(int axis, double *dummy=NULL)
cSimpleVector alim(int axis=All, double *dummy=NULL)
#define USING_NAMESPACE_SDH
std::vector< std::vector< int > > finger_axis_index
Mapping of finger index, finger axis index to axis index:
Base class for exceptions in the SDHLibrary-CPP.
std::vector< double > f_min_velocity_v
Minimum allowed axis velocity (in internal units (degrees/second)), including the virtual axis.
std::vector< double > GetAxisLimitVelocity(std::vector< int > const &axes)
std::vector< int > all_real_axes
A vector with indices of all real axes (in natural order), excluding the virtual axis.
static const cUnitConverter uc_angular_velocity_radians_per_second
Converter for angular velocieties: external unit = radians/second.
std::vector< double > SetAxisValueVector(std::vector< int > const &axes, std::vector< double > const &values, pSetFunction ll_set, pGetFunction ll_get, cUnitConverter const *uc, std::vector< double > const &min_values, std::vector< double > const &max_values, char const *name)
std::vector< double > GetAxisEnable(std::vector< int > const &axes)
@ eMCM_HOLD
The motor currents used after "gripping" with a GripHand() command (i.e. "holding")
Very simple class to measure elapsed time.
cSDHSerial comm_interface
The object to interface with the SDH attached via serial RS232 or CAN or TCP.
@ eAS_POSITIONING
the goal position has not been reached yet
cSimpleVector state(int axis=All, double *dummy=NULL)
std::vector< eAxisState > GetAxisActualState(std::vector< int > const &axes)
virtual bool IsOpen(void)
cSDH(bool _use_radians=false, bool _use_fahrenheit=false, int _debug_level=0)
Constructor of cSDH class.
int GetFingerAxisIndex(int iFinger, int iFingerAxis)
@ eCT_VELOCITY_ACCELERATION
velocity controller with acceleration ramp, velocities and accelerations of axes are controlled indep...
std::vector< double > GetAxisMinAngle(std::vector< int > const &axes)
cSimpleVector tpap(int axis=All, double *angle=NULL)
This file contains nothing but C/C++ defines with the name of the project itself (PROJECT_NAME) and t...
double MoveAxis(std::vector< int >const &axes, bool sequ=true)
std::vector< double > GetAxisTargetAngle(std::vector< int > const &axes)
std::vector< double > f_max_acceleration_v
Maximum allowed axis acceleration (in internal units (degrees/(second * second))),...
virtual bool IsOpen(void)
std::vector< double > GetAxisValueVector(std::vector< int > const &axes, pGetFunction ll_get, cUnitConverter const *uc, char const *name)
double(cUnitConverter::* pDoubleUnitConverterFunction)(double) const
Type of a pointer to a function like 'double SDH::cUnitConverter::ToExternal( double ) const' or 'dou...
const cUnitConverter * uc_angle
unit convert for (axis) angles: default = #SDH::cSDH::uc_angle_degrees
cDBG cdbg
debug stream to print colored debug messages
const cUnitConverter * uc_angular_velocity
unit convert for (axis) angular velocities: default = #SDH::cSDH::uc_angular_velocity_degrees_per_sec...
std::vector< double > GetAxisMotorCurrent(std::vector< int > const &axes, eMotorCurrentMode mode=eMCM_MOVE)
double Elapsed(void) const
Return time in seconds elapsed between the time stored in the object and now.
void SetAxisTargetAngle(std::vector< int > const &axes, std::vector< double > const &angles)
static const cUnitConverter uc_position_meter
Converter for position: external unit = meter.
eVelocityProfile vp(eVelocityProfile velocity_profile=eVP_INVALID)
Derived exception class for exceptions related to communication between the SDHLibrary and the SDH.
std::vector< double > GetAxisActualAngle(std::vector< int > const &axes)
static const cUnitConverter uc_angular_acceleration_radians_per_second_squared
Converter for angular velocieties: external unit = radians/second.
static const cUnitConverter uc_time_seconds
Default converter for times (internal unit == external unit): seconds.
std::vector< double > GetAxisMaxAngle(std::vector< int > const &axes)
Tp map(Function f, Tp sequence)
int NUMBER_OF_AXES_PER_FINGER
The number of axis per finger (for finger 1 this includes the "virtual" base axis)
void AdjustLimits(cSDHBase::eControllerType controller)
eControllerType controller_type
cached value of the axis controller type
void OpenRS232(int _port=0, unsigned long _baudrate=115200, double _timeout=-1, char const *_device_format_string="/dev/ttyS%d")
@ eCT_DIMENSION
Endmarker and dimension.
eControllerType GetController(void)
bool IsVirtualAxis(int iAxis)
Return true if index iAxis refers to a virtual axis.
const cUnitConverter * uc_motor_current
unit converter for motor curent: default = #SDH::cSDH::uc_motor_current_ampere
@ eCT_VELOCITY
velocity controller, velocities of axes are controlled independently (not implemented in SDH firmware...
std::vector< int > all_fingers
A vector with indices of all fingers (in natural order)
std::vector< double > f_max_angle_v
Maximum allowed axis angles (in internal units (degrees)), including the virtual axis.
void OpenCAN_ESD(int _net=0, unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42)
char const  * GetFirmwareRelease(void)
void SetColor(char const *color)
double l1
length of limb 1 (proximal joint to distal joint) in mm
eControllerType
An enum for all possible SDH internal controller types (order must match that in the SDH firmware in ...
#define PROJECT_RELEASE
Release name of the whole software project (a.k.a. as the "version" of the project).
void OpenCAN_PEAK(unsigned long _baudrate=1000000, double _timeout=0.0, Int32 _id_read=43, Int32 _id_write=42, const char *_device="/dev/pcanusb0")
double MoveHand(bool sequ=true)
int CompareReleases(char const *rev1, char const *rev2)
compare release strings
double eps
epsilon value (max absolute deviation of reported values from actual hardware values) (needed since S...
Low-level communication class to access a CAN port from company PEAK (http://www.peak-system....
A simple vector implementation.
std::vector< double > GetAxisReferenceVelocity(std::vector< int >const &axes)
static const cUnitConverter uc_position_millimeter
Default converter for position (internal unit == external unit): millimeter.
double grip(double close, double velocity, bool sequ)
cSimpleVector igrip(int axis=All, double *limit=NULL)
std::vector< double > GetAxisActualVelocity(std::vector< int >const &axes)
static const cUnitConverter uc_temperature_celsius
Default converter for temparatures (internal unit == external unit): degrees celsius.
std::vector< double > GetAxisMaxAcceleration(std::vector< int > const &axes)
double grip_max_velocity
Maximum allowed grip velocity (in internal units (degrees/second))
cSimpleVector(cSDHSerial::* pGetFunction)(int, double *)
Type of a pointer to a "get-axis-values" function like cSDHSerial::p, cSDHSerial::pos,...
std::vector< double > GetFingerMaxAngle(int iFinger)
Low-level communication class to access a serial port on Cygwin and Linux.
void SetAxisMotorCurrent(std::vector< int > const &axes, std::vector< double > const &motor_currents, eMotorCurrentMode mode=eMCM_MOVE)
static char const  * GetLibraryRelease(void)
@ eCT_POSE
coordinated position controller (position per axis => "pose controller"), all axes start and stop mov...
int debug_level
debug level of this object
eVelocityProfile
An enum for all possible SDH internal velocity profile types.
std::vector< double > ones_v
Vector of nb_all_axes 1.0 values.
int NUMBER_OF_FINGERS
The number of fingers.
@ eCT_INVALID
invalid controller_type (needed for cSDHSerial::con() to indicate "read current controller type")
double ToInternal(double external) const
std::vector< double > GetFingerXYZ(int iFinger, std::vector< double > const &angles)
static const cUnitConverter uc_time_milliseconds
Converter for times: external unit = milliseconds.
Low-level communication class to access a CAN port.
std::string release_firmware
string containing the SDH firmware release of the attaced SDH (something like "0.0....
double DegToRad(double d)
const cUnitConverter uc_identity
Identity converter (internal = external)
std::vector< double > f_min_motor_current_v
Minimum allowed motor currents (in internal units (Ampere)), including the virtual axis.
std::vector< double > f_ones_v
Vector of 3 1.0 values.
std::vector< std::vector< double > > offset
double GetGripMaxVelocity(void)
std::vector< double > GetAxisTargetAcceleration(std::vector< int >const &axes)
NAMESPACE_SDH_START typedef void * tDeviceHandle
generic device handle for CAN devices
int32_t Int32
signed integer, size 4 Byte (32 Bit)
cSimpleVector pos(int axis=All, double *dummy=NULL)
Class for short, fixed maximum length text messages.
std::vector< double > GetAxisMaxVelocity(std::vector< int > const &axes)
std::vector< double > SetAxisTargetGetAxisActualVelocity(std::vector< int > const &axes, std::vector< double > const &velocities)
The base class to control the SCHUNK Dexterous Hand.
void CheckRange(double value, double minvalue, double maxvalue, char const *name="")
Check if value is in [minvalue .. maxvalue]. Throw a cSDHErrorInvalidParameter exception if not.
void SetVelocityProfile(eVelocityProfile velocity_profile)
cSimpleVector v(int axis=All, double *velocity=NULL)
void SetFingerTargetAngle(int iFinger, std::vector< double > const &angles)
cSimpleVector power(int axis=All, double *flag=NULL)
void CheckIndex(int index, int maxindex, char const *name="")
Check if index is in [0 .. maxindex-1] or All. Throw a cSDHErrorInvalidParameter exception if not.
void PDM(char const *fmt,...) SDH__attribute__((format(printf
const cUnitConverter * uc_temperature
unit convert for temperatures: default = #SDH::cSDH::uc_temperature_celsius
std::vector< double > GetAxisLimitAcceleration(std::vector< int > const &axes)
int nb_all_axes
The number of all axes including virtual axes.
std::vector< int > all_axes
A vector with indices of all axes (in natural order), including the virtual axis.
Interface of class #SDH::cCANSerial_ESD, class to access CAN bus via ESD card on cygwin/linux.
std::vector< double > _GetFingerXYZ(int fi, std::vector< double > r_angles)
std::vector< double > zeros_v
Vector of nb_all_axes 0.0 values.
@ eMCM_GRIP
The motor currents used while "gripping" with a GripHand() command.
void UpdateSettingsFromSDH()
std::vector< double > GetTemperature(std::vector< int > const &sensors)
Derived exception class for exceptions related to invalid parameters.
eAxisState
The state of an axis (see TPOSCON_STATE in global.h of the SDH firmware)
static char const  * GetFirmwareReleaseRecommended(void)
pSetFunction GetMotorCurrentModeFunction(eMotorCurrentMode mode)
std::vector< int > all_temperature_sensors
A vector with indices of all temperature sensors.
std::vector< double > SetAxisTargetGetAxisActualAngle(std::vector< int > const &axes, std::vector< double > const &angles)
std::vector< double > GetAxisTargetVelocity(std::vector< int > const &axes)
std::vector< double > f_max_motor_current_v
Maximum allowed motor currents (in internal units (Ampere)), including the virtual axis.
std::vector< double > GetFingerActualAngle(int iFinger)
void WaitAxis(std::vector< int > const &axes, double timeout=-1.0)
cSimpleVector vel(int axis=All, double *dummy=NULL)
@ eMCM_DIMENSION
Endmarker and Dimension.
std::vector< int > ToIndexVector(int index, std::vector< int > &all_replacement, int maxindex, char const *name)
bool CheckFirmwareRelease(void)
const cUnitConverter * uc_angular_acceleration
unit convert for (axis) angular accelerations: default = #SDH::cSDH::uc_angular_acceleration_degrees_...
void Open(cSerialBase *_com)
cSimpleVector(cSDHSerial::* pSetFunction)(int, double *)
Type of a pointer to a "set-axis-values" function like cSDHSerial::p, cSDHSerial::pos,...
cSimpleVector a(int axis=All, double *acceleration=NULL)
std::vector< int > finger_number_of_axes
Mapping of finger index to number of real axes of fingers:
static const cUnitConverter uc_angular_velocity_degrees_per_second
Default converter for angular velocities (internal unit == external unit): degrees / second.
std::vector< double > GetFingerMinAngle(int iFinger)
cSimpleVector ihold(int axis=All, double *limit=NULL)
void SetAxisEnable(std::vector< int > const &axes, std::vector< double > const &states)
cSimpleVector temp_electronics(void)
double ToExternal(double internal) const
@ eMCM_MOVE
The motor currents used while "moving" with a MoveHand() or MoveFinger() command.
static const cUnitConverter uc_angular_acceleration_degrees_per_second_squared
Default converter for angular accelerations (internal unit == external unit): degrees / second.
double ToRange(double v, double min, double max)
int NUMBER_OF_TEMPERATURE_SENSORS
The number of temperature sensors.
Interface of auxilliary utility functions for SDHLibrary-CPP.
double selgrip(eGraspId grip, bool sequ)
Implementation of class #SDH::cRS232, a class to access serial RS232 port with VCC compiler on Window...
std::vector< double > f_min_acceleration_v
Minimum allowed axis acceleration (in internal units (degrees/(second * second))),...
This file contains settings to make the SDHLibrary compile on differen systems:
const cUnitConverter * uc_time
unit convert for times: default = uc_time_seconds
const cUnitConverter * uc_position
unit converter for position: default = #SDH::cSDH::uc_position_millimeter
cSimpleVector ilim(int axis=All, double *limit=NULL)
static char const  * GetLibraryName(void)
This file contains the interface to class #SDH::cSDH, the end user class to access the SDH from a PC.
cSimpleVector tvav(int axis=All, double *velocity=NULL)
int NUMBER_OF_VIRTUAL_AXES
The number of virtual axes.
static const cUnitConverter uc_motor_current_milliampere
Converter for motor current: external unit = milli Ampere.
static const cUnitConverter uc_angle_radians
Converter for angles: external unit = radians.
Low-level communication class to access a CAN port from company ESD (http://www.esd....
void SetAxisTargetAcceleration(std::vector< int >const &axes, std::vector< double >const &accelerations)
Unit conversion class to convert values between physical unit systems.
cSimpleVector vlim(int axis=All, double *dummy=NULL)
virtual const char * what() const
cDBG dbg
A stream object to print colored debug messages.
cSimpleVector p(int axis=All, double *angle=NULL)
int all_axes_used
Bit field with the bits for all axes set.
void SetController(cSDHBase::eControllerType controller)
eMotorCurrentMode
the motor current can be set specifically for these modes:
eGraspId
The enum values of the known grasps.
static char const  * GetStringFromControllerType(eControllerType controller_type)
Return a ptr to a (static) string describing controller type controller_Type.
void Close(bool leave_enabled=false)
Interface of auxilliary utility functions for SDHLibrary-CPP.
static const cUnitConverter uc_angle_degrees
Default converter for angles (internal unit == external unit): degrees.
std::vector< double > f_max_velocity_v
Maximum allowed axis velocity (in internal units (degrees/second)), including the virtual axis.
double GripHand(eGraspId grip, double close, double velocity, bool sequ=true)
double l2
length of limb 2 (distal joint to fingertip) in mm
Interface of class #SDH::cRS232, a class to access serial RS232 port on cygwin/linux.
@ eAS_SPEED_MODE
axis is in speed mode
#define PROJECT_NAME
Name of the software project.
Interface of class #SDH::cTCPSerial, class to access TCP port cygwin/linux.
double MoveFinger(std::vector< int >const &fingers, bool sequ=true)
eVelocityProfile GetVelocityProfile(void)
@ All
A meta-value that means "access all possible values".
void SetFingerEnable(std::vector< int > const &fingers, std::vector< double > const &states)
std::vector< double > GetFingerEnable(std::vector< int > const &fingers)
Interface of class #SDH::cCANSerial_PEAK, class to access CAN bus via PEAK card on cygwin/linux.
std::vector< double > GetFingerTargetAngle(int iFinger)
int NUMBER_OF_AXES
The number of axes.
char const  * GetInfo(char const *what)
sdhlibrary_cpp
Author(s): Dirk Osswald 
autogenerated on Wed Mar 2 2022 01:00:58