Protected Attributes | Friends | List of all members
cSDHSerial Class Reference

The class to communicate with a SDH via RS232. More...

#include <sdhserial.h>

Inheritance diagram for cSDHSerial:
Inheritance graph
[legend]

Public Member Functions

Internal methods

 cSDHSerial (int _debug_level=0)
 Constructor of cSDHSerial. More...
 
virtual ~cSDHSerial ()
 
void Open (cSerialBase *_com)
 
void Close ()
 
virtual bool IsOpen (void)
 
void Send (char const *s, int nb_lines=All, int nb_lines_total=All, int max_retries=3)
 
void ExtractFirmwareState ()
 
double GetDuration (char *line)
 
double get_duration (void)
 
void Sync ()
 
void BinarySync (double timeout_s=0.5)
 
void SyncUnknown ()
 
cSimpleVector AxisCommand (char const *command, int axis=All, double *value=NULL)
 
cSimpleVector BinaryAxisCommand (eCommandCode command, int axis=All, double *value=NULL)
 
Setup and configuration methods

cSimpleVector pid (int axis, double *p=NULL, double *i=NULL, double *d=NULL)
 
cSimpleVector kv (int axis=All, double *kv=NULL)
 
cSimpleVector ilim (int axis=All, double *limit=NULL)
 
cSimpleVector power (int axis=All, double *flag=NULL)
 
Misc. methods

void demo (bool onoff)
 
int property (char const *propname, int value)
 
int user_errors (int value)
 
int terminal (int value)
 
int debug (int value)
 
Movement methods

cSimpleVector v (int axis=All, double *velocity=NULL)
 
cSimpleVector tvav (int axis=All, double *velocity=NULL)
 
cSimpleVector vlim (int axis=All, double *dummy=NULL)
 
cSimpleVector alim (int axis=All, double *dummy=NULL)
 
cSimpleVector a (int axis=All, double *acceleration=NULL)
 
cSimpleVector p (int axis=All, double *angle=NULL)
 
cSimpleVector tpap (int axis=All, double *angle=NULL)
 
double m (bool sequ)
 
void stop (void)
 
eVelocityProfile vp (eVelocityProfile velocity_profile=eVP_INVALID)
 
eControllerType con (eControllerType controller)
 
Diagnostic and identification methods

cSimpleVector pos (int axis=All, double *dummy=NULL)
 
cSimpleVector pos_save (int axis=All, double *value=NULL)
 
cSimpleVector ref (int axis=All, double *value=NULL)
 
cSimpleVector vel (int axis=All, double *dummy=NULL)
 
cSimpleVector rvel (int axis, double *dummy=NULL)
 
cSimpleVector state (int axis=All, double *dummy=NULL)
 
cSimpleVector temp (void)
 
cSimpleVector temp_electronics (void)
 
char * ver (void)
 
char * ver_date (void)
 
char * id (void)
 
char * sn (void)
 
char * soc (void)
 
char * soc_date (void)
 
int numaxis (void)
 
Grip methods

cSimpleVector igrip (int axis=All, double *limit=NULL)
 
cSimpleVector ihold (int axis=All, double *limit=NULL)
 
double selgrip (eGraspId grip, bool sequ)
 
double grip (double close, double velocity, bool sequ)
 
- Public Member Functions inherited from cSDHBase
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. More...
 
void CheckRange (double value, double minvalue, double maxvalue, char const *name="")
 Check if value is in [minvalue .. maxvalue]. Throw a cSDHErrorInvalidParameter exception if not. More...
 
void CheckRange (double *values, double *minvalues, double *maxvalues, char const *name="")
 Check if any value[i] in array values is in [minvalue[i] .. maxvalue[i]]. Throw a cSDHErrorInvalidParameter exception if not. More...
 
 cSDHBase (int debug_level)
 
double GetEps (void)
 Return the eps value. More...
 
cSimpleVector const & GetEpsVector (void)
 Return simple vector of number of axes epsilon values. More...
 
eErrorCode GetFirmwareState (void)
 Return the last known state of the SDH firmware. More...
 
int GetNumberOfAxes (void)
 Return the number of axes of the SDH. More...
 
int GetNumberOfFingers (void)
 Return the number of fingers of the SDH. More...
 
int GetNumberOfTemperatureSensors (void)
 Return the number of temperature sensors of the SDH. More...
 
virtual void SetDebugOutput (std::ostream *debuglog)
 change the stream to use for debug messages More...
 
virtual ~cSDHBase ()
 

Protected Attributes

cSerialBasecom
 The communication object to the serial device (RS232 port or ESD CAN net) More...
 
char const * EOL
 String to use as "End Of Line" marker when sending to SDH. More...
 
double m_sequtime
 additional time in seconds to wait for sequential execution of m command (as these are always executed non-sequentially by the SDH firmware More...
 
int nb_lines_to_ignore
 number of remaining reply lines of a previous (non-sequential) command More...
 
cSimpleStringList reply
 Space for the replies from the SDH. More...
 
- Protected Attributes inherited from cSDHBase
int all_axes_used
 Bit field with the bits for all axes set. More...
 
cDBG cdbg
 debug stream to print colored debug messages More...
 
int debug_level
 debug level of this object More...
 
double eps
 epsilon value (max absolute deviation of reported values from actual hardware values) (needed since SDH firmware limits number of digits reported) More...
 
cSimpleVector eps_v
 simple vector of 7 epsilon values More...
 
eErrorCode firmware_state
 the last known state of the SDH firmware More...
 
cSimpleVector max_angle_v
 Maximum allowed axis angles (in internal units (degrees)) More...
 
cSimpleVector min_angle_v
 simple vector of 7 0 values ??? More...
 
int NUMBER_OF_AXES
 The number of axes. More...
 
int NUMBER_OF_FINGERS
 The number of fingers. More...
 
int NUMBER_OF_TEMPERATURE_SENSORS
 The number of temperature sensors. More...
 

Friends

struct sSDHBinaryRequest
 
struct sSDHBinaryResponse
 

Additional Inherited Members

- Public Types inherited from cSDHBase
enum  { All = -1 }
 Anonymous enum (instead of define like macros) More...
 
enum  eControllerType {
  eCT_INVALID = -1, eCT_POSE = 0, eCT_VELOCITY, eCT_VELOCITY_ACCELERATION,
  eCT_DIMENSION
}
 An enum for all possible SDH internal controller types (order must match that in the SDH firmware in inc/sdh2.h) More...
 
enum  eErrorCode {
  eEC_SUCCESS = 0, eEC_NOT_AVAILABLE, eEC_NOT_INITIALIZED, eEC_ALREADY_RUNNING,
  eEC_FEATURE_NOT_SUPPORTED, eEC_INCONSISTENT_DATA, eEC_TIMEOUT, eEC_READ_ERROR,
  eEC_WRITE_ERROR, eEC_INSUFFICIENT_RESOURCES, eEC_CHECKSUM_ERROR, eEC_NOT_ENOUGH_PARAMS,
  eEC_NO_PARAMS_EXPECTED, eEC_CMD_UNKNOWN, eEC_CMD_FORMAT_ERROR, eEC_ACCESS_DENIED,
  eEC_ALREADY_OPEN, eEC_CMD_FAILED, eEC_CMD_ABORTED, eEC_INVALID_HANDLE,
  eEC_DEVICE_NOT_FOUND, eEC_DEVICE_NOT_OPENED, eEC_IO_ERROR, eEC_INVALID_PARAMETER,
  eEC_RANGE_ERROR, eEC_NO_DATAPIPE, eEC_INDEX_OUT_OF_BOUNDS, eEC_HOMING_ERROR,
  eEC_AXIS_DISABLED, eEC_OVER_TEMPERATURE, eEC_MAX_COMMANDS_EXCEEDED, eEC_INVALID_PASSWORD,
  eEC_MAX_COMMANDLINE_EXCEEDED, eEC_CRC_ERROR, eEC_NO_COMMAND, eEC_INTERNAL,
  eEC_UNKNOWN_ERROR, eEC_DIMENSION
}
 
enum  eGraspId {
  eGID_INVALID = -1, eGID_CENTRICAL = 0, eGID_PARALLEL = 1, eGID_CYLINDRICAL = 2,
  eGID_SPHERICAL = 3, eGID_DIMENSION
}
 The enum values of the known grasps. More...
 
enum  eVelocityProfile { eVP_INVALID = -1, eVP_SIN_SQUARE, eVP_RAMP, eVP_DIMENSION }
 An enum for all possible SDH internal velocity profile types. More...
 
- Static Public Member Functions inherited from cSDHBase
static char const * GetStringFromControllerType (eControllerType controller_type)
 Return a ptr to a (static) string describing controller type controller_Type. More...
 
static char const * GetStringFromErrorCode (eErrorCode error_code)
 Return a ptr to a (static) string describing error code error_code. More...
 
static char const * GetStringFromGraspId (eGraspId grasp_id)
 Return a ptr to a (static) string describing grasp id grasp_id. More...
 
- Static Protected Attributes inherited from cSDHBase
static char const * controller_type_name []
 A mapping from eControllerType controller type enums to strings with human readable controller type names. More...
 
static char const * firmware_error_codes []
 A mapping from eErrorCode error code enums to strings with human readable error messages. More...
 
static char const * grasp_id_name []
 A mapping from eGraspId grasp id enums to strings with human readable grasp id names. More...
 

Detailed Description

The class to communicate with a SDH via RS232.

End-Users should NOT use this class directly! The interface of cSDHSerial is subject to change in future releases. End users should use the class cSDH instead, as that interface is considered more stable.


Definition at line 91 of file sdhserial.h.

Constructor & Destructor Documentation

◆ cSDHSerial()

cSDHSerial::cSDHSerial ( int  _debug_level = 0)

Constructor of cSDHSerial.

Parameters
_debug_level: debug level of the created object. If the debug_level of an object is > 0 then it will output debug messages. (forwared to constructor of base class)

String to use as "End Of Line" marker when sending to SDH

Definition at line 238 of file sdhserial.cpp.

◆ ~cSDHSerial()

virtual cSDHSerial::~cSDHSerial ( )
inlinevirtual

virtual destructor to make compiler happy

Definition at line 143 of file sdhserial.h.

Member Function Documentation

◆ a()

cSimpleVector cSDHSerial::a ( int  axis = All,
double *  acceleration = NULL 
)

Get/Set target acceleration for axis. (NOT the actual acceleration!)

  • If axis is All and acceleration is None then a NUMBER_OF_AXES-list of the actually set target accelerations is returned
  • If axis is a single number and acceleration is None then the target acceleration for that axis is returned.
  • If axis and acceleration are single numbers then the target acceleration for that axis is set (and returned).
  • If axis is All and acceleration is a NUMBER_OF_AXES-vector then all axes target accelerations are set accordingly, the NUMBER_OF_AXES-list is returned.

Accelerations are set/reported in degrees per second squared.

Definition at line 952 of file sdhserial.cpp.

◆ alim()

cSimpleVector cSDHSerial::alim ( int  axis = All,
double *  dummy = NULL 
)

Get acceleration limits.

  • If axis is All then a NUMBER_OF_AXES-list of the acceleration limits is returned
  • If axis is a single number then the acceleration limit for that axis is returned.

dummy parameter is just needed to make this function have the same signature as e.g. v(), so it can be used as a function pointer.

Acceleration limits are reported in degrees per (second*second).

Definition at line 945 of file sdhserial.cpp.

◆ AxisCommand()

cSimpleVector cSDHSerial::AxisCommand ( char const *  command,
int  axis = All,
double *  value = NULL 
)

Get/Set values.

  • If axis is All and value is None then a NUMBER_OF_AXES-list of the actual values read from the SDH is returned
  • If axis is a single number and value is None then the actual value for that axis is read from the SDH and is returned
  • If axis and value are single numbers then that value is set for that axis and returned.
  • If axis is All and value is a NUMBER_OF_AXES-vector then all axes values are set accordingly, a NUMBER_OF_AXES-list is returned.

Definition at line 641 of file sdhserial.cpp.

◆ BinaryAxisCommand()

cSimpleVector cSDHSerial::BinaryAxisCommand ( eCommandCode  command,
int  axis = All,
double *  value = NULL 
)

Get/Set values using binary mode.

  • If axis is All and value is None then a NUMBER_OF_AXES-list of the actual values read from the SDH is returned
  • If axis is a single number and value is None then the actual value for that axis is read from the SDH and is returned
  • If axis and value are single numbers then that value is set for that axis and returned.
  • If axis is All and value is a NUMBER_OF_AXES-vector then all axes values are set accordingly, a NUMBER_OF_AXES-list is returned.

Definition at line 725 of file sdhserial.cpp.

◆ BinarySync()

void cSDHSerial::BinarySync ( double  timeout_s = 0.5)

Read all available bytes within timeout_s seconds to resync execution of PC and SDH.

Definition at line 607 of file sdhserial.cpp.

◆ Close()

void cSDHSerial::Close ( void  )

Close connection to serial port.

Definition at line 374 of file sdhserial.cpp.

◆ con()

cSDHBase::eControllerType cSDHSerial::con ( eControllerType  controller)

Get/set controller type.

If controller is < 0 then the actually set controller is read from the SDH firmware and returned. Else the given controller type is set in the SDH firmware if valid.

Definition at line 1049 of file sdhserial.cpp.

◆ debug()

int cSDHSerial::debug ( int  value)

Definition at line 909 of file sdhserial.cpp.

◆ demo()

void cSDHSerial::demo ( bool  onoff)

Enable/disable SCHUNK demo

Definition at line 878 of file sdhserial.cpp.

◆ ExtractFirmwareState()

void cSDHSerial::ExtractFirmwareState ( )

Try to extract the state of the SDH firmware from the last reply

Definition at line 518 of file sdhserial.cpp.

◆ get_duration()

double cSDHSerial::get_duration ( void  )

Send get_duration command. Returns the calculated duration of the currently configured movement (target positions, velocities, accelerations and velocity profile.

return the expected duration of the execution of the command in seconds

Definition at line 562 of file sdhserial.cpp.

◆ GetDuration()

double cSDHSerial::GetDuration ( char *  line)

Return duration of the execution of a SDH command as reported by line

Definition at line 546 of file sdhserial.cpp.

◆ grip()

double cSDHSerial::grip ( double  close,
double  velocity,
bool  sequ 
)

send "grip=close,velocity" command to SDH close : [0.0 .. 1.0] where 0.0 is 'fully opened' and 1.0 is 'fully closed' velocity : ]0.0 .. 100.0] where 0.0 (not allowed) is very slow and 100.0 is very fast

If sequ is True then wait until SDH hardware fully executed the command. Else return immediately and do not wait until SDH hardware fully executed the command.

This seems to work with sin square velocity profile only, so the velocity profile is switched to that if necessary.

return the expected duration of the execution of the command in seconds

Definition at line 1277 of file sdhserial.cpp.

◆ id()

char * cSDHSerial::id ( void  )

Return id of SDH

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1172 of file sdhserial.cpp.

◆ igrip()

cSimpleVector cSDHSerial::igrip ( int  axis = All,
double *  limit = NULL 
)

Get/Set motor current limits for grip commands

  • If axis is All and limit is None then a NUMBER_OF_AXES-list of the actually set motor current limits is returned
  • If axis is a single number and limit is None then the motor current limit for that axis is returned.
  • If axis and limit are single numbers then the motor current limit for that axis is set (and returned).
  • If axis is All and limit is a NUMBER_OF_AXES-vector then all axes motor current limits are set accordingly, the NUMBER_OF_AXES-list is returned.

Definition at line 1215 of file sdhserial.cpp.

◆ ihold()

cSimpleVector cSDHSerial::ihold ( int  axis = All,
double *  limit = NULL 
)

Get/Set motor current limits for hold commands

  • If axis is All and limit is None then a NUMBER_OF_AXES-list of the actually set motor current limits is returned
  • If axis is a single number and limit is None then the motor current limit for that axis is returned.
  • If axis and limit are single numbers then the motor current limit for that axis is set (and returned).
  • If axis is All and limit is a NUMBER_OF_AXES-vector then all axes motor current limits are set accordingly, the NUMBER_OF_AXES-list is returned.

Definition at line 1222 of file sdhserial.cpp.

◆ ilim()

cSimpleVector cSDHSerial::ilim ( int  axis = All,
double *  limit = NULL 
)

Get/Set actual motor current limit for m command

  • If axis is All and limit is None then a NUMBER_OF_AXES-list of the actually set motor current limits is returned
  • If axis is a single number and limit is None then the motor current limit for that axis is returned.
  • If axis and limit are single numbers then the motor current limit for that axis is set (and returned).
  • If axis is All and limit is a NUMBER_OF_AXES-vector then all axes motor current limits are set accordingly, the NUMBER_OF_AXES-list is returned.

Definition at line 851 of file sdhserial.cpp.

◆ IsOpen()

bool cSDHSerial::IsOpen ( void  )
virtual

Return true if connection to SDH firmware/hardware is open

Implements cSDHBase.

Definition at line 381 of file sdhserial.cpp.

◆ kv()

cSimpleVector cSDHSerial::kv ( int  axis = All,
double *  kv = NULL 
)

Get/Set kv parameter

  • If axis is All and kv is None then a NUMBER_OF_AXES-list of the actually set kv parameters is returned
  • If axis is a single number and kv is None then the kv parameter for that axis is returned.
  • If axis and kv are single numbers then the kv parameter for that axis is set (and returned).
  • If axis is All and kv is a NUMBER_OF_AXES-vector then all axes kv parameters are set accordingly, NUMBER_OF_AXES-list is returned.
Bug:
With SDH firmware 0.0.2.9 kv() might not respond kv value correctly in case it was changed before. With SDH firmwares 0.0.2.10 and newer this now works.
=> Resolved in SDH firmware 0.0.2.10

Definition at line 820 of file sdhserial.cpp.

◆ m()

double cSDHSerial::m ( bool  sequ)

Send move command. Moves all enabled axes to their previously set target angle. The movement duration is determined by that axis that takes longest with its actually set velocity. The actual velocity of all other axes is set so that all axes begin and end their movements synchronously.

If sequ is True then wait until SDH hardware fully executed the command. Else return immediately and do not wait until SDH hardware fully executed the command.

return the expected duration of the execution of the command in seconds

Definition at line 985 of file sdhserial.cpp.

◆ numaxis()

int cSDHSerial::numaxis ( void  )

Return number of axis of SDH

Definition at line 1204 of file sdhserial.cpp.

◆ Open()

void cSDHSerial::Open ( cSerialBase _com)

Open the serial device and check connection to SDH by querying the SDH firmware version

Parameters
_com- ptr to the serial device to use

This may throw an exception on failure.

The serial port on the PC-side can be opened successfully even if no SDH is attached. Therefore this routine tries to read the SDH firmware version with a 1s timeout after the port is opened. If the SDH does not reply in time then

  • an error message is printed on stderr,
  • the port is closed
  • and a cSerialBaseException* exception is thrown.
Bug:
SCHUNK-internal bugzilla ID: Bug 1517
With SDH firmware 0.0.3.x the first connection to a newly powered up SDH can yield an error especially when connecting via TCP.
=> Resolved in SDHLibrary-C++ 0.0.2.10

Definition at line 293 of file sdhserial.cpp.

◆ p()

cSimpleVector cSDHSerial::p ( int  axis = All,
double *  angle = NULL 
)

Get/Set target angle for axis. (NOT the actual angle!)

  • If axis is All and angle is None then a NUMBER_OF_AXES-list of the actually set target angles is returned
  • If axis is a single number and angle is None then the target angle for that axis is returned.
  • If axis and angle are single numbers then the target angle for that axis is set (and returned).
  • If axis is All and angle is a NUMBER_OF_AXES-vector then all axes target angles are set accordingly, the NUMBER_OF_AXES-list is returned.

Angles are set/reported in degrees.

Definition at line 963 of file sdhserial.cpp.

◆ pid()

cSimpleVector cSDHSerial::pid ( int  axis,
double *  p = NULL,
double *  i = NULL,
double *  d = NULL 
)

Get/Set PID controller parameters

  • axis must be a single number: the index of the axis to get/set
  • If p,i,d are None then a list of the actually set PID controller parameters of the axis is returned
  • If p,i,d are numbers then the PID controller parameters for that axis are set (and returned).
Bug:
With SDH firmware 0.0.2.9 pid() might not respond pid values correctly in case these were changed before. With SDH firmwares 0.0.2.10 and newer this now works.
=> Resolved in SDH firmware 0.0.2.10

Definition at line 800 of file sdhserial.cpp.

◆ pos()

cSimpleVector cSDHSerial::pos ( int  axis = All,
double *  dummy = NULL 
)

Get actual angle/s of axis/axes.

  • If axis is All then a NUMBER_OF_AXES-vector of the actual axis angles is returned
  • If axis is a single number then the actual angle of that axis is returned.

Angles are reported in degrees.

Remarks
dummy ptr is never used, but needed nonetheless to make the signature of the function the same as for the other axis-access functions. This way a pointer to it can be used as a pointer to the other functions, which is needed by the generic cSDH::SetAxisValue and cSDH::GetAxisValue functions.

Definition at line 1068 of file sdhserial.cpp.

◆ pos_save()

cSimpleVector cSDHSerial::pos_save ( int  axis = All,
double *  value = NULL 
)

Save actual angle/s to non volatile memory. (Usefull for axes that dont have an absolute encoder)

  • If value is None then an exception is thrown since this is NOT usefull if any axis has an absolute encoder that the LLC knows about since these positions will be invalidated at the next start
  • If axis and value are single numbers then that axis is saved.
  • If axis is All and value is a NUMBER_OF_AXES-vector then all axes are saved if the corresponding value is 1.
  • This will yield a E_RANGE_ERROR if any of the given values is not 0 or 1

Definition at line 1078 of file sdhserial.cpp.

◆ power()

cSimpleVector cSDHSerial::power ( int  axis = All,
double *  flag = NULL 
)

Get/Set actual power state

  • If axis is All and flag is None then a NUMBER_OF_AXES-list of the actually set power states is returned
  • If axis is a single number and flag is None then the power state for that axis is returned.
  • If axis is a single number and flag is a single number or a boolean value then the power state for that axis is set (and returned).
  • If axis is All and flag is a NUMBER_OF_AXES-vector then all axes power states are set accordingly, the NUMBER_OF_AXES-list is returned.
  • If axis is All and flag is a a single number or a boolean value then all axes power states are set to that value, the NUMBER_OF_AXES-list is returned.

Definition at line 862 of file sdhserial.cpp.

◆ property()

int cSDHSerial::property ( char const *  propname,
int  value 
)

Set named property

Valid propnames are:

  • "user_errors"
  • "terminal"
  • "debug"

Definition at line 885 of file sdhserial.cpp.

◆ ref()

cSimpleVector cSDHSerial::ref ( int  axis = All,
double *  value = NULL 
)

Do reference movements with selected axes. (Usefull for axes that dont have an absolute encoder)

each value must be either

  • 0 : do not reference
  • 1 : reference till mechanical block in positive direction
  • 2 : reference till mechanical block in negative direction
  • If axis and value are single numbers then that axis is referenced as requested
  • If axis is All and value is a NUMBER_OF_AXES-vector then all axes are referenced as requested.
  • This will yield a E_RANGE_ERROR if any of the given values is not 0 or 1 or 2

Definition at line 1085 of file sdhserial.cpp.

◆ rvel()

cSimpleVector cSDHSerial::rvel ( int  axis,
double *  dummy = NULL 
)

Get current reference angular velocity/s of axis/axes. The reference angular velocity is used by the eCT_VELOCITY_ACCELERATION controller type only.

  • If axis is All then a NUMBER_OF_AXES-vector of the current reference velocities is returned
  • If axis is a single number then the current reference angular velocity of that axis is returned.

Angular velocities are reported in degrees/second.

Remarks
  • dummy ptr is never used, but needed nonetheless to make the signature of the function the same as for the other axis-access functions. This way a pointer to it can be used as a pointer to the other functions, which is needed by the generic cSDH::SetAxisValue and cSDH::GetAxisValue functions.
  • the underlying rvel command of the SDH firmware is not available in SDH firmwares prior to 0.0.2.6. For such hands calling rvel will fail miserably.

Definition at line 1107 of file sdhserial.cpp.

◆ selgrip()

double cSDHSerial::selgrip ( eGraspId  grip,
bool  sequ 
)

Send "selgrip grip" command to SDH. Where grip is in [0..eGID_DIMENSION-1] or one of the eGraspId enums.

If sequ is True then wait until SDH hardware fully executed the command. Else return immediately and do not wait until SDH hardware fully executed the command.

This seems to work with sin square velocity profile only, so the velocity profile is switched to that if necessary.

return the expected duration of the execution of the command in seconds

Definition at line 1229 of file sdhserial.cpp.

◆ Send()

void cSDHSerial::Send ( char const *  s,
int  nb_lines = All,
int  nb_lines_total = All,
int  max_retries = 3 
)

Send command string s+EOL to com and read reply according to nb_lines.

If nb_lines == All then reply lines are read until a line without "@" prefix is found. If nb_lines != All it is the number of lines to read.

firmware_state is set according to reply (if read) nb_lines_total contains the total number of lines replied for the s command. If fewer lines are read then nb_lines_total-nb_lines will be remembered to be ignored before the next command can be sent.

Return a list of all read lines of the reply from the SDH hardware.

Definition at line 389 of file sdhserial.cpp.

◆ sn()

char * cSDHSerial::sn ( void  )

Return sn of SDH

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1180 of file sdhserial.cpp.

◆ soc()

char * cSDHSerial::soc ( void  )

Return soc (System On Chip) ID of SDH

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1188 of file sdhserial.cpp.

◆ soc_date()

char * cSDHSerial::soc_date ( void  )

Return date of soc (System On Chip) ID of SDH

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1196 of file sdhserial.cpp.

◆ state()

cSimpleVector cSDHSerial::state ( int  axis = All,
double *  dummy = NULL 
)

Get actual state/s of axis/axes.

A state of 0 means "not moving" while 1 means "moving".

  • If axis is All then a NUMBER_OF_AXES-vector of the actual axis states is returned
  • If axis is a single number then the actual state of that axis is returned.

Definition at line 1118 of file sdhserial.cpp.

◆ stop()

void cSDHSerial::stop ( void  )

Stop sdh.

Will NOT interrupt a previous "selgrip" or "grip" command, only an "m" command!

Definition at line 1023 of file sdhserial.cpp.

◆ Sync()

void cSDHSerial::Sync ( )

Read all pending lines from SDH to resync execution of PC and SDH.

Definition at line 591 of file sdhserial.cpp.

◆ SyncUnknown()

void cSDHSerial::SyncUnknown ( )

Read an unknown number of lines from SDH to resync execution of PC and SDH.

Definition at line 616 of file sdhserial.cpp.

◆ temp()

cSimpleVector cSDHSerial::temp ( void  )

Get actual temperatures of the axis motors

Returns a list of the actual controller and driver temperature in degrees celsius.

Definition at line 1129 of file sdhserial.cpp.

◆ temp_electronics()

cSimpleVector cSDHSerial::temp_electronics ( void  )

Get actual temperatures of the electronics, i.e. teh FPGA and the PCB. (FPGA = Field Programmable Gate Array = the reprogrammable chip with the soft processors) (PCB = Printed Circuit Board)

Returns a list of the actual controller and driver temperature in degrees celsius.

Definition at line 1141 of file sdhserial.cpp.

◆ terminal()

int cSDHSerial::terminal ( int  value)

Definition at line 902 of file sdhserial.cpp.

◆ tpap()

cSimpleVector cSDHSerial::tpap ( int  axis = All,
double *  angle = NULL 
)

Set target angle and get actual angle for axis.

  • If axis is All and angle is None then a NUMBER_OF_AXES-list of the actual angles is returned
  • If axis is a single number and angle is None then the actual angle for that axis is returned.
  • If axis and angle are single numbers then the target angle for that axis is set and the actual angles are returned.
  • If axis is All and angle is a NUMBER_OF_AXES-vector then all axes target angles are set accordingly, the NUMBER_OF_AXES-list of actual angles is returned.

Angles are set/reported in degrees.

Definition at line 974 of file sdhserial.cpp.

◆ tvav()

cSimpleVector cSDHSerial::tvav ( int  axis = All,
double *  velocity = NULL 
)

Set target velocity and get actual velocity!)

The default velocity is 40 deg/s for axes 0-6 in eCT_POSE controller type. The default velocity is 0.0 deg/s for axes 0-6 in eCT_VELOCITY and eCT_VELOCITY_ACCELERATION controller types.

  • If axis is All and velocity is None then a NUMBER_OF_AXES-list of the actual velocities is returned
  • If axis is a single number and velocity is None then the actual velocity for that axis is returned.
  • If axis and velocity are single numbers then the target velocity for that axis is set and the actual velocity is returned.
  • If axis is All and velocity is a NUMBER_OF_AXES-vector then all axes target velocities are set accordingly, the NUMBER_OF_AXES-list of actual velocities is returned.

Velocities are set/reported in degrees per second.

Bug:
With SDH firmware < 0.0.1.0 axis 0 can go no faster than 14 deg/s
=> Resolved in SDH firmware 0.0.1.0

Definition at line 927 of file sdhserial.cpp.

◆ user_errors()

int cSDHSerial::user_errors ( int  value)

Definition at line 895 of file sdhserial.cpp.

◆ v()

cSimpleVector cSDHSerial::v ( int  axis = All,
double *  velocity = NULL 
)

Get/Set target velocity. (NOT the actual velocity!)

The default velocity is 40 deg/s for axes 0-6 in eCT_POSE controller type. The default velocity is 0.0 deg/s for axes 0-6 in eCT_VELOCITY and eCT_VELOCITY_ACCELERATION controller types.

  • If axis is All and velocity is None then a NUMBER_OF_AXES-list of the actually set target velocities is returned
  • If axis is a single number and velocity is None then the target velocity for that axis is returned.
  • If axis and velocity are single numbers then the target velocity for that axis is set (and returned).
  • If axis is All and velocity is a NUMBER_OF_AXES-vector then all axes target velocities are set accordingly, the NUMBER_OF_AXES-list is returned.

Velocities are set/reported in degrees per second.

Bug:
With SDH firmware < 0.0.1.0 axis 0 can go no faster than 14 deg/s
=> Resolved in SDH firmware 0.0.1.0

Definition at line 916 of file sdhserial.cpp.

◆ vel()

cSimpleVector cSDHSerial::vel ( int  axis = All,
double *  dummy = NULL 
)

Get actual angular velocity/s of axis/axes.

  • If axis is All then a NUMBER_OF_AXES-vector of the actual axis angular velocities is returned
  • If axis is a single number then the actual angular velocity of that axis is returned.

Angular velocities are reported in degrees/second.

Remarks
dummy ptr is never used, but needed nonetheless to make the signature of the function the same as for the other axis-access functions. This way a pointer to it can be used as a pointer to the other functions, which is needed by the generic cSDH::SetAxisValue and cSDH::GetAxisValue functions.

Definition at line 1096 of file sdhserial.cpp.

◆ ver()

char * cSDHSerial::ver ( void  )

Return version of SDH firmware

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1156 of file sdhserial.cpp.

◆ ver_date()

char * cSDHSerial::ver_date ( void  )

Return date of SDH firmware

Attention
The string returned is stored internally in this object and might be overwritten by the next command to this object

Definition at line 1164 of file sdhserial.cpp.

◆ vlim()

cSimpleVector cSDHSerial::vlim ( int  axis = All,
double *  dummy = NULL 
)

Get velocity limits.

  • If axis is All then a NUMBER_OF_AXES-list of the velocity limits is returned
  • If axis is a single number then the velocity limit for that axis is returned.

dummy parameter is just needed to make this function have the same signature as e.g. v(), so it can be used as a function pointer.

Velocity limits are reported in degrees per second.

Definition at line 938 of file sdhserial.cpp.

◆ vp()

cSDHBase::eVelocityProfile cSDHSerial::vp ( eVelocityProfile  velocity_profile = eVP_INVALID)

Get/set velocity profile.

If velocity_profile is < 0 then the actually set velocity profile is read from the SDH firmware and returned. Else the given velocity_profile type is set in the SDH firmware if valid.

Definition at line 1030 of file sdhserial.cpp.

Friends And Related Function Documentation

◆ sSDHBinaryRequest

friend struct sSDHBinaryRequest
friend

Definition at line 93 of file sdhserial.h.

◆ sSDHBinaryResponse

friend struct sSDHBinaryResponse
friend

Definition at line 94 of file sdhserial.h.

Member Data Documentation

◆ com

cSerialBase* cSDHSerial::com
protected

The communication object to the serial device (RS232 port or ESD CAN net)

Definition at line 108 of file sdhserial.h.

◆ EOL

char const* cSDHSerial::EOL
protected

String to use as "End Of Line" marker when sending to SDH.

Definition at line 105 of file sdhserial.h.

◆ m_sequtime

double cSDHSerial::m_sequtime
protected

additional time in seconds to wait for sequential execution of m command (as these are always executed non-sequentially by the SDH firmware

Definition at line 102 of file sdhserial.h.

◆ nb_lines_to_ignore

int cSDHSerial::nb_lines_to_ignore
protected

number of remaining reply lines of a previous (non-sequential) command

Definition at line 115 of file sdhserial.h.

◆ reply

cSimpleStringList cSDHSerial::reply
protected

Space for the replies from the SDH.

Definition at line 112 of file sdhserial.h.


The documentation for this class was generated from the following files:


sdhlibrary_cpp
Author(s): Dirk Osswald
autogenerated on Mon Feb 28 2022 23:41:52