![]() |
3.9.1
|
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) |
DRD header file.
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.
ID | [default=-1] device ID (see multiple devices section for details) |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdClose | ( | char | ID | ) |
Close the connection to a particular device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdEnableFilter | ( | bool | on, |
char | ID | ||
) |
Enable or disable motion filtering for subsequent calls to drdTrackPos() or drdTrackEnc().
on | true to enable motion filtering, false to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK drdGetCtrlFreq | ( | char | ID | ) |
This function returns the average refresh rate of the control loop (in kHz) since the function was last called.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdGetDeviceID | ( | ) |
Return the ID of the current default device.
double __SDK drdGetEncDGain | ( | char | ID | ) |
Retrieve the D term of the PID controller that regulates the base joint positions.
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK drdGetEncIGain | ( | char | ID | ) |
Retrieve the I term of the PID controller that regulates the base joint positions.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdGetEncMoveParam | ( | double * | amax, |
double * | vmax, | ||
double * | jerk, | ||
char | ID | ||
) |
Retrieve encoder positioning trajectory generation 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) |
double __SDK drdGetEncPGain | ( | char | ID | ) |
Retrieve the P term of the PID controller that regulates the base joint positions.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdGetEncTrackParam | ( | double * | amax, |
double * | vmax, | ||
double * | jerk, | ||
char | ID | ||
) |
Retrieve encoder tracking trajectory generation 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) |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
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.
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 first joint in [rad] |
ob | [out] device orientation around the second joint in [rad] |
og | [out] device orientation around the third joint 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) |
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()
.int __SDK drdGetPosMoveParam | ( | double * | amax, |
double * | vmax, | ||
double * | jerk, | ||
char | ID | ||
) |
Retrieve Cartesian positioning trajectory generation 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) |
int __SDK drdGetPosTrackParam | ( | double * | amax, |
double * | vmax, | ||
double * | jerk, | ||
char | ID | ||
) |
Retrieve Cartesian tracking trajectory generation 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) |
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.
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) |
prio
) is always set to the calling thread priority, even when the call returns an error.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.
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.
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) |
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()
.int __SDK drdHold | ( | char | ID | ) |
Immediately make the robot hold its current position. All motion commands are abandoned.
ID | [default=-1] device ID (see multiple devices section for details) |
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().
ID | [default=-1] device ID (see multiple devices section for details) |
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().
ID | [default=-1] device ID (see multiple devices section for details) |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK drdIsRunning | ( | char | ID | ) |
Checks the state of the robotic control thread for a particular device.
ID | [default=-1] device ID (see multiple devices section for details) |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdLock | ( | unsigned char | mask, |
bool | init, | ||
char | ID | ||
) |
Depending on the value of the mask
parameter, either:
This function only applies to devices equipped with mechanical locks, and will return an error when called on other devices.
mask | 0 to disengage the locks, any other value to park the device and engage the locks |
init | if 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) |
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.
p | target positions/orientations in [m] or as described in rad |
block | if 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) |
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.
enc | target encoder positions |
block | if 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) |
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.
enc0 | target encoder position on axis 0 [] |
enc1 | target encoder position on axis 1 [] |
enc2 | target encoder position on axis 2 [] |
block | if 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) |
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.
pg | target gripper opening distance in [m] |
block | if 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) |
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.
px | target position on the X axis in [m] |
py | target position on the Y axis in [m] |
pz | target position on the Z axis in [m] |
block | if 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) |
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.
oa | target orientation around the first joint in [rad] |
ob | target orientation around the second joint in [rad] |
og | target orientation around the third joint in [rad] |
block | if 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) |
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.
int __SDK drdOpenID | ( | char | index | ) |
Open a connection to one particular compatible device connected to the system. The order in which devices are opened persists until devices are added or removed. If the device at the specified index is already opened, its device ID is returned.
index | the device enumeration index, as assigned by the underlying operating system (must be between 0 and the number of devices connected to the system) |
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.
on | true to enable gripper regulation, false to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
on | true to enable base regulation, false to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
on | true to enable wrist regulation, false to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
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.
gain | D parameter of the PID regulator |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
gain | I parameter of the PID regulator |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdSetEncMoveParam | ( | double | amax, |
double | vmax, | ||
double | jerk, | ||
char | ID | ||
) |
Set encoder positioning trajectory generation parameters.
amax | max acceleration (m/s2) |
vmax | max velocity (m/s) |
jerk | jerk (m/s3) |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
gain | P parameter of the PID regulator |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdSetEncTrackParam | ( | double | amax, |
double | vmax, | ||
double | jerk, | ||
char | ID | ||
) |
Set encoder tracking trajectory generation parameters.
amax | max acceleration (m/s2) |
vmax | max velocity (m/s) |
jerk | jerk (m/s3) |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
fx | translation force along X axis [N] |
fy | translation force along Y axis [N] |
fz | translation force along Z axis [N] |
tx | torque around the X axis in [Nm] |
ty | torque around the Y axis in [Nm] |
tz | torque around the Z axis in [Nm] |
fg | gripper force in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
fx | translation force along X axis [N] |
fy | translation force along Y axis [N] |
fz | translation force along Z axis [N] |
t0 | wrist axis 0 torque command [Nm] |
t1 | wrist axis 1 torque command [Nm] |
t2 | wrist axis 2 torque command [Nm] |
fg | gripper force in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
scale | the joint torque scaling factor (must be between 0.0 and 1.0) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdSetPosMoveParam | ( | double | amax, |
double | vmax, | ||
double | jerk, | ||
char | ID | ||
) |
Set Cartesian positioning trajectory generation parameters.
amax | max acceleration (m/s2) |
vmax | max velocity (m/s) |
jerk | jerk (m/s3) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdSetPosTrackParam | ( | double | amax, |
double | vmax, | ||
double | jerk, | ||
char | ID | ||
) |
Set Cartesian tracking trajectory generation parameters.
amax | max acceleration (m/s2) |
vmax | max velocity (m/s) |
jerk | jerk (m/s3) |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
prio | calling thread priority level (value is system dependent) |
ctrlprio | control thread priority level (value is system dependent) |
ID | [default=-1] device ID (see multiple devices section for details) |
prio
) is always applied to the calling thread, even when the call returns an error.void __SDK drdSleep | ( | double | sec | ) |
Suspend the calling thread for a given duration specified in [s]-> The sleep resolution is machine and OS dependent.
sec | sleep duration in [s] |
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.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK drdStop | ( | bool | frc, |
char | ID | ||
) |
Stop the robotic control loop for the given robot.
frc | if 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) |
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.
p | target positions/orientations in [m] or as described in rad |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
enc | target encoder positions |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
enc0 | target encoder position on axis 0 [] |
enc1 | target encoder position on axis 1 [] |
enc2 | target encoder position on axis 2 [] |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
pg | target gripper opening distance in [m] |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
px | target position on the X axis in [m] |
py | target position on the Y axis in [m] |
pz | target position on the Z axis in [m] |
ID | [default=-1] device ID (see multiple devices section for details) |
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.
oa | target orientation around the first joint in [rad] |
ob | target orientation around the second joint in [rad] |
og | target orientation around the third joint in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
void __SDK drdWaitForTick | ( | char | ID | ) |
Synchronization function: calling this function will block until the next iteration of the control loop begins.