3.7.2
Functions
drdc.h File Reference

DRD header file. More...

Functions

int __SDK drdOpen ()
 
int __SDK drdOpenID (char ID)
 
int __SDK drdSetDevice (char ID)
 
int __SDK drdGetDeviceID ()
 
int __SDK drdClose (char ID=-1)
 
bool __SDK drdIsSupported (char ID=-1)
 
bool __SDK drdIsRunning (char ID=-1)
 
bool __SDK drdIsMoving (char ID=-1)
 
bool __SDK drdIsFiltering (char ID=-1)
 
double __SDK drdGetTime ()
 
void __SDK drdSleep (double sec)
 
void __SDK drdWaitForTick (char ID=-1)
 
bool __SDK drdIsInitialized (char ID=-1)
 
int __SDK drdAutoInit (char ID=-1)
 
int __SDK drdCheckInit (char ID=-1)
 
int __SDK drdGetPositionAndOrientation (double *px, double *py, double *pz, double *oa, double *ob, double *og, double *pg, double matrix[3][3], char ID=-1)
 
int __SDK drdGetVelocity (double *vx, double *vy, double *vz, double *wx, double *wy, double *wz, double *vg, char ID=-1)
 
double __SDK drdGetCtrlFreq (char ID=-1)
 
int __SDK drdStart (char ID=-1)
 
int __SDK drdRegulatePos (bool on, char ID=-1)
 
int __SDK drdRegulateRot (bool on, char ID=-1)
 
int __SDK drdRegulateGrip (bool on, char ID=-1)
 
int __SDK drdSetForceAndTorqueAndGripperForce (double fx, double fy, double fz, double tx, double ty, double tz, double fg, char ID=-1)
 
int __SDK drdSetForceAndWristJointTorquesAndGripperForce (double fx, double fy, double fz, double t0, double t1, double t2, double fg, char ID=-1)
 
int __SDK drdEnableFilter (bool on, char ID=-1)
 
int __SDK drdMoveToPos (double px, double py, double pz, bool block=true, char ID=-1)
 
int __SDK drdMoveToRot (double oa, double ob, double og, bool block=true, char ID=-1)
 
int __SDK drdMoveToGrip (double pg, bool block=true, char ID=-1)
 
int __SDK drdMoveTo (double p[DHD_MAX_DOF], bool block=true, char ID=-1)
 
int __SDK drdMoveToEnc (int enc0, int enc1, int enc2, bool block=true, char ID=-1)
 
int __SDK drdMoveToAllEnc (int enc[DHD_MAX_DOF], bool block=true, char ID=-1)
 
int __SDK drdTrackPos (double px, double py, double pz, char ID=-1)
 
int __SDK drdTrackRot (double oa, double ob, double og, char ID=-1)
 
int __SDK drdTrackGrip (double pg, char ID=-1)
 
int __SDK drdTrack (double p[DHD_MAX_DOF], char ID=-1)
 
int __SDK drdTrackEnc (int enc0, int enc1, int enc2, char ID=-1)
 
int __SDK drdTrackAllEnc (int enc[DHD_MAX_DOF], char ID=-1)
 
int __SDK drdHold (char ID=-1)
 
int __SDK drdLock (unsigned char mask, bool init, char ID=-1)
 
int __SDK drdStop (bool frc=false, char ID=-1)
 
int __SDK drdGetPriorities (int *prio, int *ctrlprio, char ID=-1)
 
int __SDK drdSetPriorities (int prio, int ctrlprio, char ID=-1)
 
int __SDK drdSetEncPGain (double gain, char ID=-1)
 
double __SDK drdGetEncPGain (char ID=-1)
 
int __SDK drdSetEncIGain (double gain, char ID=-1)
 
double __SDK drdGetEncIGain (char ID=-1)
 
int __SDK drdSetEncDGain (double gain, char ID=-1)
 
double __SDK drdGetEncDGain (char ID=-1)
 
int __SDK drdSetMotRatioMax (double scale, char ID=-1)
 
double __SDK drdGetMotRatioMax (char ID=-1)
 
int __SDK drdSetEncMoveParam (double amax, double vmax, double jerk, char ID=-1)
 
int __SDK drdSetEncTrackParam (double amax, double vmax, double jerk, char ID=-1)
 
int __SDK drdSetPosMoveParam (double amax, double vmax, double jerk, char ID=-1)
 
int __SDK drdSetPosTrackParam (double amax, double vmax, double jerk, char ID=-1)
 
int __SDK drdGetEncMoveParam (double *amax, double *vmax, double *jerk, char ID=-1)
 
int __SDK drdGetEncTrackParam (double *amax, double *vmax, double *jerk, char ID=-1)
 
int __SDK drdGetPosMoveParam (double *amax, double *vmax, double *jerk, char ID=-1)
 
int __SDK drdGetPosTrackParam (double *amax, double *vmax, double *jerk, char ID=-1)
 

Detailed Description

DRD header file.

Function Documentation

◆ drdAutoInit()

int __SDK drdAutoInit ( char  ID)

Performs automatic initialization of that particular robot by robotically moving to a known position and reseting encoder counters to their correct values.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Note
In order to make regulation as stable as possible, drdAutoInit() automatically increases the priority level of the regulation thread to a higher value than the normal system process priority.
See also
drdCheckInit()
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdCheckInit()

int __SDK drdCheckInit ( char  ID)

Check the validity of that particular robot initialization by robotically sweeping all endstops and comparing their joint space position to expected values (stored in each device internal memory). If the robot is not yet initialized, this function will first perform the same initialization routine as drdAutoInit() before running the endstop check.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Note
In order to make regulation as stable as possible, drdCheckInit() automatically increases the priority level of the regulation thread to a higher value than the normal system process priority.
See also
drdAutoInit()
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdClose()

int __SDK drdClose ( char  ID)

Close the connection to a particular device.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdEnableFilter()

int __SDK drdEnableFilter ( bool  on,
char  ID 
)

Enable or disable motion filtering for subsequent calls to drdTrackPos() or drdTrackEnc().

Parameters
ontrue to enable motion filtering, false to disable it
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetCtrlFreq()

double __SDK drdGetCtrlFreq ( char  ID)

This function returns the average refresh rate of the control loop (in kHz) since the function was last called.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetDeviceID()

int __SDK drdGetDeviceID ( )

Return the ID of the current default device.

Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetEncDGain()

double __SDK drdGetEncDGain ( char  ID)

Retrieve the D term of the PID controller that regulates the base joint positions.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
The P gain of the PID regulator.

◆ drdGetEncIGain()

double __SDK drdGetEncIGain ( char  ID)

Retrieve the I term of the PID controller that regulates the base joint positions.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
The P gain of the PID regulator.

◆ drdGetEncMoveParam()

int __SDK drdGetEncMoveParam ( double *  amax,
double *  vmax,
double *  jerk,
char  ID 
)

Retrieve encoder positioning trajectory generation parameters.

Parameters
amax[out]max acceleration (m/s2)
vmax[out]max velocity (m/s)
jerk[out]jerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetEncPGain()

double __SDK drdGetEncPGain ( char  ID)

Retrieve the P term of the PID controller that regulates the base joint positions.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
The P gain of the PID regulator.

◆ drdGetEncTrackParam()

int __SDK drdGetEncTrackParam ( double *  amax,
double *  vmax,
double *  jerk,
char  ID 
)

Retrieve encoder tracking trajectory generation parameters.

Parameters
amax[out]max acceleration (m/s2)
vmax[out]max velocity (m/s)
jerk[out]jerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetMotRatioMax()

double __SDK drdGetMotRatioMax ( char  ID)

Retrieve the maximum joint torque applied to all regulated joints expressed as a fraction of the maximum torque available for each joint.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
The maximum joint torque ratio (between 0.0 and 1.0)

◆ drdGetPositionAndOrientation()

int __SDK drdGetPositionAndOrientation ( double *  px,
double *  py,
double *  pz,
double *  oa,
double *  ob,
double *  og,
double *  pg,
double  matrix[3][3],
char  ID 
)

Retrieve the position of the end-effector in Cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.

Parameters
px[out] device position on the X axis in [m]
py[out] device position on the Y axis in [m]
pz[out] device position on the Z axis in [m]
oa[out] device orientation around the X axis in [rad]
ob[out] device orientation around the Y axis in [rad]
og[out] device orientation around the Z axis in [rad]
pg[out] device gripper opening gap in [m]
matrix[out] orientation matrix frame
ID[default=-1] device ID (see multiple devices section for details)
Note
This function differs from dhdGetPositionAndOrientationFrame() in that it is synchronized with the robotic control loop. As a result, it does not impact control performance and returns faster than dhdGetPositionAndOrientationFrame().
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetPosMoveParam()

int __SDK drdGetPosMoveParam ( double *  amax,
double *  vmax,
double *  jerk,
char  ID 
)

Retrieve Cartesian positioning trajectory generation parameters.

Parameters
amax[out]max acceleration (m/s2)
vmax[out]max velocity (m/s)
jerk[out]jerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetPosTrackParam()

int __SDK drdGetPosTrackParam ( double *  amax,
double *  vmax,
double *  jerk,
char  ID 
)

Retrieve Cartesian tracking trajectory generation parameters.

Parameters
amax[out]max acceleration (m/s2)
vmax[out]max velocity (m/s)
jerk[out]jerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetPriorities()

int __SDK drdGetPriorities ( int *  prio,
int *  ctrlprio,
char  ID 
)

This function makes it possible to retrieve the priority of the control thread and the calling thread. Thread priority is system dependent, as described in thread priorities.

Parameters
prio[out] calling thread priority level (value is system dependent)
ctrlprio[out] control thread priority level (value is system dependent)
ID[default=-1] device ID (see multiple devices section for details)
Note
The first argument (prio) is always set to the calling thread priority, even when the call returns an error.
See also
drdSetPriorities()
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdGetTime()

double __SDK drdGetTime ( )

Returns the current value from the high-resolution system counter in [s]. The resolution of the system counter may be machine-dependent, as it usually derived from one of the CPU clocks signals. The time returned is guaranteed to be monotonous.

Returns
The current time in [s]

◆ drdGetVelocity()

int __SDK drdGetVelocity ( double *  vx,
double *  vy,
double *  vz,
double *  wx,
double *  wy,
double *  wz,
double *  vg,
char  ID 
)

Retrieve the velocity of the end-effector position in Cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.

Parameters
vx[out] velocity along the X axis [m/s]
vy[out] velocity along the Y axis [m/s]
vz[out] velocity along the Z axis [m/s]
wx[out] angular velocity around the X axis [rad/s]
wy[out] angular velocity around the Y axis [rad/s]
wz[out] angular velocity around the Z axis [rad/s]
vg[out] gripper linear velocity [m/s]
ID[default=-1] device ID (see multiple devices section for details)
Note
This function differs from dhdGetLinearVelocity() and its relatives in that it is synchronized with the robotic control loop. As a result, it does not impact control performance and returns faster than dhdGetLinearVelocity().
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdHold()

int __SDK drdHold ( char  ID)

Immediately make the robot hold its current position. All motion commands are abandoned.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdIsFiltering()

bool __SDK drdIsFiltering ( char  ID)

Checks whether the particular robot control thread is applying a motion filter while tracking a target using drdTrackPos() or drdTrackEnc().

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
true if the motion filter is enabled, false otherwise.

◆ drdIsInitialized()

bool __SDK drdIsInitialized ( char  ID)

Checks the initialization status of a particular robot. The initialization status reflects the status of the controller RESET LED. The robot can be (re)initialized by calling drdAutoInit().

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
true if the robot is initialized, false otherwise.

◆ drdIsMoving()

bool __SDK drdIsMoving ( char  ID)

Checks whether the particular robot is moving (following a call to drdMoveToPos(), drdMoveToEnc(), drdTrackPos() or drdTrackEnc()), as opposed to holding the target position after successfully reaching it.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
true if the robot is moving, false otherwise.

◆ drdIsRunning()

bool __SDK drdIsRunning ( char  ID)

Checks the state of the robotic control thread for a particular device.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
true if the control thread is running, false otherwise.

◆ drdIsSupported()

bool __SDK drdIsSupported ( char  ID)

Determine if the device is supported out-of-the-box by the DRD. The regulation gains of supported devices are configured internally so that such devices are ready to use. Unsupported devices can still be operated with the DRD, but their regulation gains must first be configured using the drdSetEncPGain(), drdSetEncIGain() and drdSetEncDGain() functions.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
true if the device is configured internally, false otherwise.

◆ drdLock()

int __SDK drdLock ( unsigned char  mask,
bool  init,
char  ID 
)

Depending on the value of the mask parameter, either:

  • move the device to its park position and engage the locks, or
  • removes the locks

This function only applies to devices equipped with mechanical locks, and will return an error when called on other devices.

Note
Upon success, the robotic regulation is running when the function returns. If the device has just been parked, it is recommended to call drdStop() to disable regulation.
Parameters
mask0 to disengage the locks, any other value to park the device and engage the locks
initif true and mask is 0, then the device will auto-initialize before locks are engaged or after locks are disengaged
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveTo()

int __SDK drdMoveTo ( double  p[DHD_MAX_DOF],
bool  block,
char  ID 
)

Send the robot end-effector to a desired Cartesian 7-DOF configuration. The motion uses smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
ptarget positions/orientations in [m] or as described in rad
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveToAllEnc()

int __SDK drdMoveToAllEnc ( int  enc[DHD_MAX_DOF],
bool  block,
char  ID 
)

Send the robot end-effector to a desired encoder position. The motion follows a straight line in the encoder space, with smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
enctarget encoder positions
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveToEnc()

int __SDK drdMoveToEnc ( int  enc0,
int  enc1,
int  enc2,
bool  block,
char  ID 
)

Send the robot end-effector to a desired encoder position. The motion follows a straight line in the encoder space, with smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
enc0target encoder position on axis 0 []
enc1target encoder position on axis 1 []
enc2target encoder position on axis 2 []
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveToGrip()

int __SDK drdMoveToGrip ( double  pg,
bool  block,
char  ID 
)

Send the robot gripper to a desired opening distance. The motion is executed with smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
pgtarget gripper opening distance in [m]
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveToPos()

int __SDK drdMoveToPos ( double  px,
double  py,
double  pz,
bool  block,
char  ID 
)

Send the robot end-effector to a desired Cartesian position. The motion follows a straight line, with smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
pxtarget position on the X axis in [m]
pytarget position on the Y axis in [m]
pztarget position on the Z axis in [m]
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdMoveToRot()

int __SDK drdMoveToRot ( double  oa,
double  ob,
double  og,
bool  block,
char  ID 
)

Send the robot end-effector to a desired Cartesian rotation. The motion follows a straight curve, with smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Parameters
oatarget orientation around the X axis in [rad]
obtarget orientation around the Y axis in [rad]
ogtarget orientation around the Z axis in [rad]
blockif true, the call blocks until the destination is reached. If false, the call returns immediately.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdOpen()

int __SDK drdOpen ( )

Open a connection to the first compatible device connected to the system. To open connections to multiple devices, use the drdOpenID() call.

Note
If this call is successful, the default device ID is set to the newly opened device. See the multiple device section for more information on using multiple devices on the same computer.
Returns
The device ID on success, -1 otherwise.
See error management for details.
See also
drdOpenID

◆ drdOpenID()

int __SDK drdOpenID ( char  ID)

Open a connection to one particular compatible device connected to the system. The order in which devices are opened is predictable and remains the same until system configuration changes.

Parameters
IDthe device ID (must be between 0 and the number of devices connected to the system)
Note
If this call is successful, the default device ID is set to the newly opened device. See the multiple device section for more information on using multiple devices on the same computer.
Returns
The device ID on success, -1 otherwise.
See error management for details.
See also
drdOpen

◆ drdRegulateGrip()

int __SDK drdRegulateGrip ( bool  on,
char  ID 
)

Enable/disable robotic regulation of the device gripper. If regulation is disabled, the gripper can move freely and will display any force set using drdSetForceAndTorqueAndGripperForce(). If it is enabled, gripper orientation is locked and can be controlled by calling all robotic functions (e.g. drdMoveTo()). By default, gripper regulation is enabled.

Parameters
ontrue to enable gripper regulation, false to disable it
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdRegulatePos()

int __SDK drdRegulatePos ( bool  on,
char  ID 
)

Enable/disable robotic regulation of the device delta base, which provides translations. If regulation is disabled, the base can move freely and will display any force set using drdSetForceAndTorqueAndGripperForce(). If it is enabled, base position is locked and can be controlled by calling all robotic functions (e.g. drdMoveToPos()). By default, delta base regulation is enabled.

Parameters
ontrue to enable base regulation, false to disable it
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdRegulateRot()

int __SDK drdRegulateRot ( bool  on,
char  ID 
)

Enable/disable robotic regulation of the device wrist. If regulation is disabled, the wrist can move freely and will display any torque set using drdSetForceAndTorqueAndGripperForce(). If it is enabled, wrist orientation is locked and can be controlled by calling all robotic functions (e.g. drdMoveTo()). By default, wrist regulation is enabled.

Parameters
ontrue to enable wrist regulation, false to disable it
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetDevice()

int __SDK drdSetDevice ( char  ID)

Select the default device that will receive the API commands. The API supports multiple devices. This routine allows the programmer to decide which device the API dhd_single_device_call single-device calls will address. Any subsequent API call that does not specifically mention the device ID in its parameter list will be sent to that device.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetEncDGain()

int __SDK drdSetEncDGain ( double  gain,
char  ID 
)

Set the D term of the PID controller that regulates the base joint positions. In practice, this affects the velocity of the regulation.

Parameters
gainD parameter of the PID regulator
ID[default=-1] device ID (see multiple devices section for details)

◆ drdSetEncIGain()

int __SDK drdSetEncIGain ( double  gain,
char  ID 
)

Set the I term of the PID controller that regulates the base joint positions. In practice, this affects the precision of the regulation.

Parameters
gainI parameter of the PID regulator
ID[default=-1] device ID (see multiple devices section for details)

◆ drdSetEncMoveParam()

int __SDK drdSetEncMoveParam ( double  amax,
double  vmax,
double  jerk,
char  ID 
)

Set encoder positioning trajectory generation parameters.

Parameters
amaxmax acceleration (m/s2)
vmaxmax velocity (m/s)
jerkjerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetEncPGain()

int __SDK drdSetEncPGain ( double  gain,
char  ID 
)

Set the P term of the PID controller that regulates the base joint positions. In practice, this affects the stiffness of the regulation.

Parameters
gainP parameter of the PID regulator
ID[default=-1] device ID (see multiple devices section for details)

◆ drdSetEncTrackParam()

int __SDK drdSetEncTrackParam ( double  amax,
double  vmax,
double  jerk,
char  ID 
)

Set encoder tracking trajectory generation parameters.

Parameters
amaxmax acceleration (m/s2)
vmaxmax velocity (m/s)
jerkjerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetForceAndTorqueAndGripperForce()

int __SDK drdSetForceAndTorqueAndGripperForce ( double  fx,
double  fy,
double  fz,
double  tx,
double  ty,
double  tz,
double  fg,
char  ID 
)

Apply force, torques and gripper force to all non-regulated, actuated DOFs of the device. The regulated DOFs can be selected using drdRegulatePos(), drdRegulateRot() and drdRegulateGrip(). The requested force is ignored for all regulated DOFs. You must use this function instead of all dhdSetForce() calls if the robotic regulation thread is running to prevent interfering with the regulation commands.

Parameters
fxtranslation force along X axis [N]
fytranslation force along Y axis [N]
fztranslation force along Z axis [N]
txtorque around the X axis in [Nm]
tytorque around the Y axis in [Nm]
tztorque around the Z axis in [Nm]
fggripper force in [N]
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetForceAndWristJointTorquesAndGripperForce()

int __SDK drdSetForceAndWristJointTorquesAndGripperForce ( double  fx,
double  fy,
double  fz,
double  t0,
double  t1,
double  t2,
double  fg,
char  ID 
)

Apply force, wrist joint torques and gripper force to all non-regulated, actuated DOFs of the device. The regulated DOFs can be selected using drdRegulatePos(), drdRegulateRot() and drdRegulateGrip(). The requested force is ignored for all regulated DOFs. You must use this function instead of all dhdSetForce() calls if the robotic regulation thread is running to prevent interfering with the regulation commands.

Parameters
fxtranslation force along X axis [N]
fytranslation force along Y axis [N]
fztranslation force along Z axis [N]
t0WRIST axis 0 torque command [Nm]
t1WRIST axis 1 torque command [Nm]
t2WRIST axis 2 torque command [Nm]
fggripper force in [N]
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetMotRatioMax()

int __SDK drdSetMotRatioMax ( double  scale,
char  ID 
)

Set the maximum joint torque applied to all regulated joints expressed as a fraction of the maximum torque available for each joint.

In practice, this limits the maximum regulation torque (in joint space), making it potentially safer to operate in environments where humans or delicate obstacles are present.

Parameters
scalethe joint torque scaling factor (must be between 0.0 and 1.0)
ID[default=-1] device ID (see multiple devices section for details)

◆ drdSetPosMoveParam()

int __SDK drdSetPosMoveParam ( double  amax,
double  vmax,
double  jerk,
char  ID 
)

Set Cartesian positioning trajectory generation parameters.

Parameters
amaxmax acceleration (m/s2)
vmaxmax velocity (m/s)
jerkjerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetPosTrackParam()

int __SDK drdSetPosTrackParam ( double  amax,
double  vmax,
double  jerk,
char  ID 
)

Set Cartesian tracking trajectory generation parameters.

Parameters
amaxmax acceleration (m/s2)
vmaxmax velocity (m/s)
jerkjerk (m/s3)
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSetPriorities()

int __SDK drdSetPriorities ( int  prio,
int  ctrlprio,
char  ID 
)

This function makes it possible to adjust the priority of the control thread and the calling thread. Thread priority is system dependent, as described in thread priorities.

Parameters
priocalling thread priority level (value is system dependent)
ctrlpriocontrol thread priority level (value is system dependent)
ID[default=-1] device ID (see multiple devices section for details)
Note
Please keep in mind that administrator/superuser access is required on many platforms in order to increase thread priority.
The first argument (prio) is always applied to the calling thread, even when the call returns an error.
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdSleep()

void __SDK drdSleep ( double  sec)

Suspend the calling thread for a given duration specified in [s]-> The sleep resolution is machine and OS dependent.

Parameters
secsleep duration in [s]

◆ drdStart()

int __SDK drdStart ( char  ID)

Start the robotic control loop for the given robot. The robot must be initialized (either manually or with drdAutoInit()) before drdStart() can be called successfully.

Parameters
ID[default=-1] device ID (see multiple devices section for details)
Note
In order to make regulation as stable as possible, drdStart() automatically increases the priority level of the regulation thread to a higher value than the normal system process priority. The priority level of the regulation thread can be changed by calling drdSetPriorities().
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdStop()

int __SDK drdStop ( bool  frc,
char  ID 
)

Stop the robotic control loop for the given robot.

Parameters
frcif false, puts the device in BRAKE mode upon exiting, otherwise leaves the device in FORCE mode. See the DHD documentation for device mode details.
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrack()

int __SDK drdTrack ( double  p[DHD_MAX_DOF],
char  ID 
)

Send the robot end-effector to a desired Cartesian 7-DOF configuration. If motion filters are enabled, the motion follows a smooth acceleration/deceleration constraint on each Cartesian axis. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target position is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
ptarget positions/orientations in [m] or as described in rad
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrackAllEnc()

int __SDK drdTrackAllEnc ( int  enc[DHD_MAX_DOF],
char  ID 
)

Send the robot end-effector to a desired encoder position. If motion filters are enabled, the motion follows a smooth acceleration/deceleration constraint on each encoder axis. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target position is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
enctarget encoder positions
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrackEnc()

int __SDK drdTrackEnc ( int  enc0,
int  enc1,
int  enc2,
char  ID 
)

Send the robot end-effector to a desired encoder position. If motion filters are enabled, the motion follows a smooth acceleration/deceleration constraint on each encoder axis. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target position is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
enc0target encoder position on axis 0 []
enc1target encoder position on axis 1 []
enc2target encoder position on axis 2 []
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrackGrip()

int __SDK drdTrackGrip ( double  pg,
char  ID 
)

Send the robot gripper to a desired opening distance. If motion filters are enabled, the motion follows a smooth acceleration/deceleration. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target opening distance is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
pgtarget gripper opening distance in [m]
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrackPos()

int __SDK drdTrackPos ( double  px,
double  py,
double  pz,
char  ID 
)

Send the robot end-effector to a desired Cartesian position. If motion filters are enabled, the motion follows a smooth acceleration/deceleration constraint on each Cartesian axis. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target position is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
pxtarget position on the X axis in [m]
pytarget position on the Y axis in [m]
pztarget position on the Z axis in [m]
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdTrackRot()

int __SDK drdTrackRot ( double  oa,
double  ob,
double  og,
char  ID 
)

Send the robot end-effector to a desired Cartesian orientation. If motion filters are enabled, the motion follows a smooth acceleration/deceleration curve along each Cartesian axis. The acceleration and velocity profiles can be controlled by adjusting the trajectory generation parameters.

Note
WARNING - If motion filters are disabled, the target orientation is immediately applied as the new regulation target, leading to potential discontinuities.
Parameters
oatarget orientation around the X axis in [rad]
obtarget orientation around the Y axis in [rad]
ogtarget orientation around the Z axis in [rad]
ID[default=-1] device ID (see multiple devices section for details)
Returns
0 on success, -1 otherwise.
See error management for details.

◆ drdWaitForTick()

void __SDK drdWaitForTick ( char  ID)

Synchronization function: calling this function will block until the next iteration of the control loop begins.