Protected Attributes | Friends
cSDHSerial Class Reference

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

#include <sdhserial.h>

Inheritance diagram for cSDHSerial:
Inheritance graph
[legend]

List of all members.

Public Member Functions

Internal methods

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

cSimpleVector pid (int axis, double *p=NULL, double *i=NULL, double *d=NULL) throw (cSDHLibraryException*)
cSimpleVector kv (int axis=All, double *kv=NULL) throw (cSDHLibraryException*)
cSimpleVector ilim (int axis=All, double *limit=NULL) throw (cSDHLibraryException*)
cSimpleVector power (int axis=All, double *flag=NULL) throw (cSDHLibraryException*)
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) throw (cSDHLibraryException*)
cSimpleVector tvav (int axis=All, double *velocity=NULL) throw (cSDHLibraryException*)
cSimpleVector vlim (int axis=All, double *dummy=NULL) throw (cSDHLibraryException*)
cSimpleVector alim (int axis=All, double *dummy=NULL) throw (cSDHLibraryException*)
cSimpleVector a (int axis=All, double *acceleration=NULL) throw (cSDHLibraryException*)
cSimpleVector p (int axis=All, double *angle=NULL) throw (cSDHLibraryException*)
cSimpleVector tpap (int axis=All, double *angle=NULL) throw (cSDHLibraryException*)
double m (bool sequ) throw (cSDHLibraryException*)
void stop (void) throw (cSDHLibraryException*)
eVelocityProfile vp (eVelocityProfile velocity_profile=eVP_INVALID) throw (cSDHLibraryException*)
eControllerType con (eControllerType controller) throw (cSDHLibraryException*)
Diagnostic and identification methods

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

cSimpleVector igrip (int axis=All, double *limit=NULL) throw (cSDHLibraryException*)
cSimpleVector ihold (int axis=All, double *limit=NULL) throw (cSDHLibraryException*)
double selgrip (eGraspId grip, bool sequ) throw (cSDHLibraryException*)
double grip (double close, double velocity, bool sequ) throw (cSDHLibraryException*)

Protected Attributes

cSerialBasecom
 The communication object to the serial device (RS232 port or ESD CAN net)
char const * EOL
 String to use as "End Of Line" marker when sending to SDH.
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
int nb_lines_to_ignore
 number of remaining reply lines of a previous (non-sequential) command
cSimpleStringList reply
 Space for the replies from the SDH.

Friends

struct sSDHBinaryRequest
struct sSDHBinaryResponse

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 108 of file sdhserial.h.


Constructor & Destructor Documentation

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)
virtual cSDHSerial::~cSDHSerial ( ) [inline, virtual]

virtual destructor to make compiler happy

Definition at line 160 of file sdhserial.h.


Member Function Documentation

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

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.

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

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).

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

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.
cSimpleVector cSDHSerial::BinaryAxisCommand ( eCommandCode  command,
int  axis = All,
double *  value = NULL 
) throw (cSDHLibraryException*)

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.
void cSDHSerial::BinarySync ( double  timeout_s = 0.5) throw (cSDHErrorCommunication*)

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

Close connection to serial port.

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.

int cSDHSerial::debug ( int  value)
void cSDHSerial::demo ( bool  onoff)

Enable/disable SCHUNK demo

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

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

double cSDHSerial::GetDuration ( char *  line) throw (cSDHErrorCommunication*)

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

double cSDHSerial::grip ( double  close,
double  velocity,
bool  sequ 
) throw (cSDHLibraryException*)

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

char* cSDHSerial::id ( void  ) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::igrip ( int  axis = All,
double *  limit = NULL 
) throw (cSDHLibraryException*)

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.
cSimpleVector cSDHSerial::ihold ( int  axis = All,
double *  limit = NULL 
) throw (cSDHLibraryException*)

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.
cSimpleVector cSDHSerial::ilim ( int  axis = All,
double *  limit = NULL 
) throw (cSDHLibraryException*)

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.
virtual bool cSDHSerial::IsOpen ( void  ) [virtual]

Return true if connection to SDH firmware/hardware is open

Implements cSDHBase.

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

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
double cSDHSerial::m ( bool  sequ) throw (cSDHLibraryException*)

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

int cSDHSerial::numaxis ( void  ) throw (cSDHLibraryException*)

Return number of axis of SDH

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.

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

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.

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

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
cSimpleVector cSDHSerial::pos ( int  axis = All,
double *  dummy = NULL 
) throw (cSDHLibraryException*)

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.
cSimpleVector cSDHSerial::pos_save ( int  axis = All,
double *  value = NULL 
) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::power ( int  axis = All,
double *  flag = NULL 
) throw (cSDHLibraryException*)

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.
int cSDHSerial::property ( char const *  propname,
int  value 
)

Set named property

Valid propnames are:

  • "user_errors"
  • "terminal"
  • "debug"
cSimpleVector cSDHSerial::ref ( int  axis = All,
double *  value = NULL 
) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::rvel ( int  axis,
double *  dummy = NULL 
) throw (cSDHLibraryException*)

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.
double cSDHSerial::selgrip ( eGraspId  grip,
bool  sequ 
) throw (cSDHLibraryException*)

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

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

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.

char* cSDHSerial::sn ( void  ) throw (cSDHLibraryException*)

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
char* cSDHSerial::soc ( void  ) throw (cSDHLibraryException*)

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
char* cSDHSerial::soc_date ( void  ) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::state ( int  axis = All,
double *  dummy = NULL 
) throw (cSDHLibraryException*)

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.
void cSDHSerial::stop ( void  ) throw (cSDHLibraryException*)

Stop sdh.

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

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

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

Get actual temperatures of the axis motors

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

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.

int cSDHSerial::terminal ( int  value)
cSimpleVector cSDHSerial::tpap ( int  axis = All,
double *  angle = NULL 
) throw (cSDHLibraryException*)

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.

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

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
int cSDHSerial::user_errors ( int  value)
cSimpleVector cSDHSerial::v ( int  axis = All,
double *  velocity = NULL 
) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::vel ( int  axis = All,
double *  dummy = NULL 
) throw (cSDHLibraryException*)

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.
char* cSDHSerial::ver ( void  ) throw (cSDHLibraryException*)

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
char* cSDHSerial::ver_date ( void  ) throw (cSDHLibraryException*)

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
cSimpleVector cSDHSerial::vlim ( int  axis = All,
double *  dummy = NULL 
) throw (cSDHLibraryException*)

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.

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.


Friends And Related Function Documentation

friend struct sSDHBinaryRequest [friend]

Definition at line 110 of file sdhserial.h.

friend struct sSDHBinaryResponse [friend]

Definition at line 111 of file sdhserial.h.


Member Data Documentation

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

Definition at line 125 of file sdhserial.h.

char const* cSDHSerial::EOL [protected]

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

Definition at line 122 of file sdhserial.h.

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 119 of file sdhserial.h.

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

Definition at line 132 of file sdhserial.h.

Space for the replies from the SDH.

Definition at line 129 of file sdhserial.h.


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


schunk_sdh
Author(s): Mathias Luedtke , Florian Weisshardt
autogenerated on Sat Jun 8 2019 20:25:21