DHD header file. More...
Functions | |
int __SDK | dhdErrorGetLast () |
const char *__SDK | dhdErrorGetLastStr () |
const char *__SDK | dhdErrorGetStr (int error) |
void __SDK | dhdEnableSimulator (bool on) |
int __SDK | dhdGetDeviceCount () |
int __SDK | dhdGetAvailableCount () |
int __SDK | dhdSetDevice (char ID) |
int __SDK | dhdGetDeviceID () |
int __SDK | dhdGetSerialNumber (ushort *sn, char ID=-1) |
int __SDK | dhdOpen () |
int __SDK | dhdOpenType (int type) |
int __SDK | dhdOpenSerial (int serial) |
int __SDK | dhdOpenID (char ID) |
int __SDK | dhdClose (char ID=-1) |
int __SDK | dhdCheckControllerMemory (char ID=-1) |
int __SDK | dhdStop (char ID=-1) |
int __SDK | dhdGetComMode (char ID=-1) |
int __SDK | dhdEnableForce (uchar val, char ID=-1) |
int __SDK | dhdEnableGripperForce (uchar val, char ID=-1) |
int __SDK | dhdGetSystemType (char ID=-1) |
int __SDK | dhdGetSystemRev (char ID=-1) |
const char *__SDK | dhdGetSystemName (char ID=-1) |
int __SDK | dhdGetVersion (double *ver, char ID=-1) |
int __SDK | dhdGetVersionStr (char *buffer, size_t size, char ID=-1) |
void __SDK | dhdGetSDKVersion (int *major, int *minor, int *release, int *revision) |
const char *__SDK | dhdGetSDKVersionStr () |
int __SDK | dhdGetComponentVersionStr (uint32_t component, char *buffer, size_t size, char ID=-1) |
int __SDK | dhdGetStatus (int status[DHD_MAX_STATUS], char ID=-1) |
int __SDK | dhdGetDeviceAngleRad (double *angle, char ID=-1) |
int __SDK | dhdGetDeviceAngleDeg (double *angle, char ID=-1) |
int __SDK | dhdGetEffectorMass (double *mass, char ID=-1) |
ulong __SDK | dhdGetSystemCounter () |
int __SDK | dhdGetButton (int index, char ID=-1) |
uint __SDK | dhdGetButtonMask (char ID=-1) |
int __SDK | dhdSetOutput (uint output, char ID=-1) |
bool __SDK | dhdIsLeftHanded (char ID=-1) |
bool __SDK | dhdHasBase (char ID=-1) |
bool __SDK | dhdHasWrist (char ID=-1) |
bool __SDK | dhdHasActiveWrist (char ID=-1) |
bool __SDK | dhdHasGripper (char ID=-1) |
bool __SDK | dhdHasActiveGripper (char ID=-1) |
int __SDK | dhdReset (char ID=-1) |
int __SDK | dhdResetWrist (char ID=-1) |
int __SDK | dhdWaitForReset (int timeout=0, char ID=-1) |
int __SDK | dhdSetStandardGravity (double g, char ID=-1) |
int __SDK | dhdSetGravityCompensation (int val=DHD_ON, char ID=-1) |
int __SDK | dhdSetBrakes (int val=DHD_ON, char ID=-1) |
int __SDK | dhdSetDeviceAngleRad (double angle, char ID=-1) |
int __SDK | dhdSetDeviceAngleDeg (double angle, char ID=-1) |
int __SDK | dhdSetEffectorMass (double mass, char ID=-1) |
int __SDK | dhdGetPosition (double *px, double *py, double *pz, char ID=-1) |
int __SDK | dhdGetForce (double *fx, double *fy, double *fz, char ID=-1) |
int __SDK | dhdSetForce (double fx, double fy, double fz, char ID=-1) |
int __SDK | dhdGetOrientationRad (double *oa, double *ob, double *og, char ID=-1) |
int __SDK | dhdGetOrientationDeg (double *oa, double *ob, double *og, char ID=-1) |
int __SDK | dhdGetPositionAndOrientationRad (double *px, double *py, double *pz, double *oa, double *ob, double *og, char ID=-1) |
int __SDK | dhdGetPositionAndOrientationDeg (double *px, double *py, double *pz, double *oa, double *ob, double *og, char ID=-1) |
int __SDK | dhdGetPositionAndOrientationFrame (double *px, double *py, double *pz, double matrix[3][3], char ID=-1) |
int __SDK | dhdGetForceAndTorque (double *fx, double *fy, double *fz, double *tx, double *ty, double *tz, char ID=-1) |
int __SDK | dhdSetForceAndTorque (double fx, double fy, double fz, double tx, double ty, double tz, char ID=-1) |
int __SDK | dhdGetOrientationFrame (double matrix[3][3], char ID=-1) |
int __SDK | dhdGetGripperAngleDeg (double *a, char ID=-1) |
int __SDK | dhdGetGripperAngleRad (double *a, char ID=-1) |
int __SDK | dhdGetGripperGap (double *g, char ID=-1) |
int __SDK | dhdGetGripperThumbPos (double *px, double *py, double *pz, char ID=-1) |
int __SDK | dhdGetGripperFingerPos (double *px, double *py, double *pz, char ID=-1) |
double __SDK | dhdGetComFreq (char ID=-1) |
int __SDK | dhdSetForceAndGripperForce (double fx, double fy, double fz, double fg, char ID=-1) |
int __SDK | dhdSetForceAndTorqueAndGripperForce (double fx, double fy, double fz, double tx, double ty, double tz, double fg, char ID=-1) |
int __SDK | dhdGetForceAndTorqueAndGripperForce (double *fx, double *fy, double *fz, double *tx, double *ty, double *tz, double *f, char ID=-1) |
int __SDK | dhdConfigLinearVelocity (int ms=DHD_VELOCITY_WINDOW, int mode=DHD_VELOCITY_WINDOWING, char ID=-1) |
int __SDK | dhdGetLinearVelocity (double *vx, double *vy, double *vz, char ID=-1) |
int __SDK | dhdConfigAngularVelocity (int ms=DHD_VELOCITY_WINDOW, int mode=DHD_VELOCITY_WINDOWING, char ID=-1) |
int __SDK | dhdGetAngularVelocityRad (double *wx, double *wy, double *wz, char ID=-1) |
int __SDK | dhdGetAngularVelocityDeg (double *wx, double *wy, double *wz, char ID=-1) |
int __SDK | dhdConfigGripperVelocity (int ms=DHD_VELOCITY_WINDOW, int mode=DHD_VELOCITY_WINDOWING, char ID=-1) |
int __SDK | dhdGetGripperLinearVelocity (double *vg, char ID=-1) |
int __SDK | dhdGetGripperAngularVelocityRad (double *wg, char ID=-1) |
int __SDK | dhdGetGripperAngularVelocityDeg (double *wg, char ID=-1) |
int __SDK | dhdEmulateButton (uchar val, char ID=-1) |
int __SDK | dhdGetBaseAngleXRad (double *angle, char ID=-1) |
int __SDK | dhdGetBaseAngleXDeg (double *angle, char ID=-1) |
int __SDK | dhdSetBaseAngleXRad (double angle, char ID=-1) |
int __SDK | dhdSetBaseAngleXDeg (double angle, char ID=-1) |
int __SDK | dhdGetBaseAngleZRad (double *angle, char ID=-1) |
int __SDK | dhdGetBaseAngleZDeg (double *angle, char ID=-1) |
int __SDK | dhdSetBaseAngleZRad (double angle, char ID=-1) |
int __SDK | dhdSetBaseAngleZDeg (double angle, char ID=-1) |
int __SDK | dhdSetVibration (double freq, double amplitude, int type=0, char ID=-1) |
int __SDK | dhdSetMaxForce (double f, char ID=-1) |
int __SDK | dhdSetMaxTorque (double t, char ID=-1) |
int __SDK | dhdSetMaxGripperForce (double fg, char ID=-1) |
double __SDK | dhdGetMaxForce (char ID=-1) |
double __SDK | dhdGetMaxTorque (char ID=-1) |
double __SDK | dhdGetMaxGripperForce (char ID=-1) |
int __SDK | dhdEnableExpertMode () |
int __SDK | dhdDisableExpertMode () |
int __SDK | dhdPreset (int val[DHD_MAX_DOF], uchar mask, char ID=-1) |
int __SDK | dhdCalibrateWrist (char ID=-1) |
int __SDK | dhdSetTimeGuard (int us, char ID=-1) |
int __SDK | dhdSetVelocityThreshold (uint val, char ID=-1) |
int __SDK | dhdGetVelocityThreshold (uint *val, char ID=-1) |
int __SDK | dhdUpdateEncoders (char ID=-1) |
int __SDK | dhdGetDeltaEncoders (int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdGetWristEncoders (int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdGetGripperEncoder (int *enc, char ID=-1) |
int __SDK | dhdGetEncoder (int index, char ID=-1) |
int __SDK | dhdSetMotor (int index, ushort val, char ID=-1) |
int __SDK | dhdSetDeltaMotor (ushort mot0, ushort mot1, ushort mot2, char ID=-1) |
int __SDK | dhdSetWristMotor (ushort mot0, ushort mot1, ushort mot2, char ID=-1) |
int __SDK | dhdSetGripperMotor (ushort mot, char ID=-1) |
int __SDK | dhdDeltaEncoderToPosition (int enc0, int enc1, int enc2, double *px, double *py, double *pz, char ID=-1) |
int __SDK | dhdDeltaPositionToEncoder (double px, double py, double pz, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdDeltaMotorToForce (ushort mot0, ushort mot1, ushort mot2, int enc0, int enc1, int enc2, double *fx, double *fy, double *fz, char ID=-1) |
int __SDK | dhdDeltaForceToMotor (double fx, double fy, double fz, int enc0, int enc1, int enc2, ushort *mot0, ushort *mot1, ushort *mot2, char ID=-1) |
int __SDK | dhdWristEncoderToOrientation (int enc0, int enc1, int enc2, double *oa, double *ob, double *og, char ID=-1) |
int __SDK | dhdWristOrientationToEncoder (double oa, double ob, double og, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdWristMotorToTorque (ushort mot0, ushort mot1, ushort mot2, int enc0, int enc1, int enc2, double *tx, double *ty, double *tz, char ID=-1) |
int __SDK | dhdWristTorqueToMotor (double ta, double tb, double tg, int enc0, int enc1, int enc2, ushort *mot0, ushort *mot1, ushort *mot2, char ID=-1) |
int __SDK | dhdGripperEncoderToAngleRad (int enc, double *a, char ID=-1) |
int __SDK | dhdGripperEncoderToGap (int enc, double *g, char ID=-1) |
int __SDK | dhdGripperAngleRadToEncoder (double a, int *enc, char ID=-1) |
int __SDK | dhdGripperGapToEncoder (double g, int *enc, char ID=-1) |
int __SDK | dhdGripperMotorToForce (ushort mot, double *f, int e[4], char ID=-1) |
int __SDK | dhdGripperForceToMotor (double f, ushort *mot, int e[4], char ID=-1) |
int __SDK | dhdSetMot (ushort mot[DHD_MAX_DOF], uchar mask=0xff, char ID=-1) |
int __SDK | dhdPreloadMot (ushort mot[DHD_MAX_DOF], uchar mask=0xff, char ID=-1) |
int __SDK | dhdGetEnc (int enc[DHD_MAX_DOF], uchar mask=0xff, char ID=-1) |
int __SDK | dhdSetBrk (uchar mask=0xff, char ID=-1) |
int __SDK | dhdGetDeltaJointAngles (double *j0, double *j1, double *j2, char ID=-1) |
int __SDK | dhdGetDeltaJacobian (double jcb[3][3], char ID=-1) |
int __SDK | dhdDeltaJointAnglesToJacobian (double j0, double j1, double j2, double jcb[3][3], char ID=-1) |
int __SDK | dhdDeltaJointTorquesExtrema (double j0, double j1, double j2, double minq[3], double maxq[3], char ID=-1) |
int __SDK | dhdDeltaGravityJointTorques (double j0, double j1, double j2, double *q0, double *q1, double *q2, char ID=-1) |
int __SDK | dhdSetDeltaJointTorques (double t0, double t1, double t2, char ID=-1) |
int __SDK | dhdDeltaEncodersToJointAngles (int enc0, int enc1, int enc2, double *j0, double *j1, double *j2, char ID=-1) |
int __SDK | dhdDeltaJointAnglesToEncoders (double j0, double j1, double j2, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdGetWristJointAngles (double *j0, double *j1, double *j2, char ID=-1) |
int __SDK | dhdGetWristJacobian (double jcb[3][3], char ID=-1) |
int __SDK | dhdWristJointAnglesToJacobian (double j0, double j1, double j2, double jcb[3][3], char ID=-1) |
int __SDK | dhdWristJointTorquesExtrema (double j0, double j1, double j2, double minq[3], double maxq[3], char ID=-1) |
int __SDK | dhdWristGravityJointTorques (double j0, double j1, double j2, double *q0, double *q1, double *q2, char ID=-1) |
int __SDK | dhdSetWristJointTorques (double t0, double t1, double t2, char ID=-1) |
int __SDK | dhdSetForceAndWristJointTorques (double fx, double fy, double fz, double t0, double t1, double t2, char ID=-1) |
int __SDK | dhdSetForceAndWristJointTorquesAndGripperForce (double fx, double fy, double fz, double t0, double t1, double t2, double fg, char ID=-1) |
int __SDK | dhdWristEncodersToJointAngles (int enc0, int enc1, int enc2, double *j0, double *j1, double *j2, char ID=-1) |
int __SDK | dhdWristJointAnglesToEncoders (double j0, double j1, double j2, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __SDK | dhdGetJointAngles (double j[DHD_MAX_DOF], char ID=-1) |
int __SDK | dhdGetJointVelocities (double v[DHD_MAX_DOF], char ID=-1) |
int __SDK | dhdGetEncVelocities (double v[DHD_MAX_DOF], char ID=-1) |
int __SDK | dhdJointAnglesToInertiaMatrix (double j[DHD_MAX_DOF], double inertia[6][6], char ID=-1) |
int __SDK | dhdSetComMode (int mode, char ID=-1) |
int __SDK | dhdSetComModePriority (int priority, char ID=-1) |
int __SDK | dhdSetWatchdog (unsigned char val, char ID=-1) |
int __SDK | dhdGetWatchdog (unsigned char *val, char ID=-1) |
int __SDK | dhdGetEncRange (int encMin[DHD_MAX_DOF], int encMax[DHD_MAX_DOF], char ID=-1) |
int __SDK | dhdGetJointAngleRange (double jmin[DHD_MAX_DOF], double jmax[DHD_MAX_DOF], char ID=-1) |
int __SDK | dhdControllerSetDevice (int device, char ID=-1) |
int __SDK | dhdReadConfigFromFile (char *filename, char ID=-1) |
bool __SDK | dhdKbHit () |
char __SDK | dhdKbGet () |
double __SDK | dhdGetTime () |
void __SDK | dhdSleep (double sec) |
int __SDK | dhdStartThread (void *func(void *), void *arg, int priority) |
DHD header file.
#define DHD_COM_MODE_ASYNC 1 |
The asynchronous USB mode is the default. The asynchronous USB mode allows the operating system to parallelise the read and write operations on the USB port. This parallel operation improves refresh rate stability by reducing communication jitter. Other factors also influence USB performance, including the choice of operating system, machine load and program optimisation.
#define DHD_COM_MODE_NETWORK 4 |
This mode is reported when connected to a haptic device using the Force Dimension network connection mode.
#define DHD_COM_MODE_SYNC 0 |
The synchronous USB mode performs USB read and write operations in sequence, allowing for a theoretical haptic refresh rate of 4 kHz. Please note that Other factors also influence USB performance, including the choice of operating system, machine load and program optimisation.
#define DHD_COM_MODE_VIRTUAL 3 |
This mode is reported when connected to a virtual device.
#define DHD_DELTA_ENC_0 0 |
Array index for encoder 0 of the DELTA structure (expert mode only).
#define DHD_DELTA_ENC_1 1 |
Array index for encoder 1 of the DELTA structure (expert mode only).
#define DHD_DELTA_ENC_2 2 |
Array index for encoder 2 of the DELTA structure (expert mode only).
#define DHD_DELTA_MOTOR_0 0 |
Array index for motor 0 of the DELTA structure (expert mode only).
#define DHD_DELTA_MOTOR_1 1 |
Array index for motor 1 of the DELTA structure (expert mode only).
#define DHD_DELTA_MOTOR_2 2 |
Array index for motor 2 of the DELTA structure (expert mode only).
#define DHD_DEVICE_CONTROLLER 81 |
Device identifier for the Force Dimension stand-alone USB 2.0 controller device.
#define DHD_DEVICE_CONTROLLER_HR 82 |
Device identifier for the Force Dimension stand-alone USB 2.0 controller device with high-resolution encoders (24bits).
#define DHD_DEVICE_CUSTOM 91 |
Device identifier for an unknown device compatible with the Force Dimension communication protocol.
#define DHD_DEVICE_DELTA3 63 |
Device identifier for the Force Dimension DELTA.3 haptic device (USB version).
#define DHD_DEVICE_FALCON 60 |
Device identifier for the Novint FALCON haptic device.
#define DHD_DEVICE_LAMBDA331 108 |
Device identifier for the right-handed version of the Force Dimension LAMBDA.7 haptic device.
#define DHD_DEVICE_LAMBDA331_LEFT 109 |
Device identifier for the left-handed version of the Force Dimension LAMBDA.7 haptic device.
#define DHD_DEVICE_NONE 0 |
Device identifier returned when no device is connected.
#define DHD_DEVICE_OMEGA3 33 |
Device identifier for the Force Dimension OMEGA.3 haptic device.
#define DHD_DEVICE_OMEGA33 34 |
Device identifier for the right-handed version of the Force Dimension OMEGA.6 haptic device.
#define DHD_DEVICE_OMEGA331 35 |
Device identifier for the right-handed version of the Force Dimension OMEGA.7 haptic device.
#define DHD_DEVICE_OMEGA331_LEFT 37 |
Device identifier for the left-handed version of the Force Dimension OMEGA.7 haptic device.
#define DHD_DEVICE_OMEGA33_LEFT 36 |
Device identifier for the left-handed version of the Force Dimension OMEGA.6 haptic device.
#define DHD_DEVICE_SIGMA331 104 |
Device identifier for the right-handed version of the Force Dimension SIGMA.7 haptic device.
#define DHD_DEVICE_SIGMA331_LEFT 105 |
Device identifier for the left-handed version of the Force Dimension SIGMA.7 haptic device.
#define DHD_MAX_BUTTONS 16 |
The maximum number of buttons the SDK can address on the Force Dimension haptic device.
#define DHD_MAX_DOF 8 |
Maximum number of encoder channels that are available.
#define DHD_MAX_STATUS 17 |
The length of the status array. See device status for details.
#define DHD_MOTOR_SATURATED 2 |
Return value used when at least one of the motors cannot deliver the requested torque. Motor groups are scaled in order to preserve force and torque direction over magnitude.
#define DHD_OFF 0 |
Applies to the device status values.
#define DHD_ON 1 |
Applies to the device status values.
#define DHD_STATUS_AXISCHECKED 16 |
A bit-wise mask that indicates the validation status of each axis. The validation status of all device axes can be assessed by calling the drdCheckInit()
function in the Force Dimension Robotic SDK (DRD). Each bit of the status value returned corresponds to a the validation status of the corresponding axis, e.g.:
#define DHD_STATUS_BRAKE 6 |
The index of the BRAKE flag in the status array. This flag indicates if the device is in BRAKE mode or not. See device modes for details.
#define DHD_STATUS_CONNECTED 1 |
The index of the connection flag in the status array. This flag indicates if the device is connected or not.
#define DHD_STATUS_ERROR 9 |
The index of the error flag in the status array. This flag indicates if the an error happened on the device controller.
#define DHD_STATUS_FORCE 5 |
The index of the FORCE flag in the status array. This flag indicates if the device is in FORCE mode or not. See device modes for details.
#define DHD_STATUS_FORCEOFFCAUSE 14 |
The event that caused forces to be disabled on the device (the last time forces were turned off). The event can be one of the following value:
DHD_FORCEOFF_NONE:
nothing has caused forces to be turned off yet DHD_FORCEOFF_BUTTON:
the force button was pushed DHD_FORCEOFF_VELOCITY:
the velocity threshold was reached DHD_FORCEOFF_WATCHDOG:
the communication watchdog kicked in DHD_FORCEOFF_SOFTWARE:
the software requested forces to be turned off, e.g. dhdEnableForce() DHD_FORCEOFF_USBDISCN:
the USB cable was disconnected DHD_FORCEOFF_DEADMAN:
the dead man switch was disconnectedNote that not all devices support all the force-disabling mechanisms listed above.
#define DHD_STATUS_GRAVITY 10 |
The index of the gravity flag in the status array. This flag indicates if the gravity compensation option is enabled or not.
#define DHD_STATUS_IDLE 4 |
The index of the IDLE flag in the status array. This flag indicates if the device is in IDLE mode or not. See device modes for details.
#define DHD_STATUS_LOCKS 15 |
The status of the locks on supported devices. The value can be either DHD_ON if the locks are engaged, DHD_OFF if the locks are disengagned, or DHD_UNDEFINED if the status of the locks is unknown.
#define DHD_STATUS_POWER 0 |
The index of the power flag in the status array. This flag indicates if the device is powered or not.
#define DHD_STATUS_REDUNDANCY 13 |
The status of the redundant encoder consistency check. For devices equipped with redundant encoders, a value of 1
indicates that the redundancy check is successful. A value of 0
is reported otherwise, or if the device does not feature redundant encoders.
#define DHD_STATUS_RESET 3 |
The index of the RESET flag in the status array. This flag indicates if the device is in RESET mode or not. See device modes for details.
#define DHD_STATUS_STARTED 2 |
The index of the start flag in the status array. This flag indicates if the device controller is running.
#define DHD_STATUS_TIMEGUARD 11 |
The index of the TimeGuard flag in the status array. This flag indicates if the TimeGuard feature is enabled or not. See TimeGuard feature for details.
#define DHD_STATUS_TORQUE 7 |
The index of the TORQUE flag in the status array. This flag indicates if the torques are active or not when the device is in FORCE mode. See device modes for details.
#define DHD_STATUS_WRIST_DETECTED 8 |
The index of the WRIST_DETECTED flag in the status array. This flag indicates if the device has a wrist or not. See device types for details.
#define DHD_STATUS_WRIST_INIT 12 |
The index of the WRIST_INIT flag in the status array. This flag indicates if the device wrist is initialized or not. See device types for details.
#define DHD_THREAD_PRIORITY_DEFAULT 0 |
This constant can be used to tell the dhdStartThread() function to use the default operating system priority level for the newly created thread.
#define DHD_THREAD_PRIORITY_HIGH 1 |
This constant can be used to tell the dhdStartThread() function to use a priority level higher than the default operating system priority for the newly created thread.
#define DHD_THREAD_PRIORITY_LOW 2 |
This constant can be used to tell the dhdStartThread() function to use a priority level lower than the default operating system priority for the newly created thread.
#define DHD_TIMEGUARD 1 |
Return value used when the TimeGuard feature prevented an unnecessary communication with the device.
#define DHD_UNDEFINED -1 |
Applies to the device status values.
#define DHD_VELOCITY_WINDOW 20 |
The default window size used by the velocity estimator. The actual time interval (or "window") can be adjusted using dhdConfigLinearVelocity, and should be modified to best suit the dynamic behavior of the device for a given application.
#define DHD_VELOCITY_WINDOWING 0 |
The default velocity estimator mode. In this mode, the velocity is estimated by comparing the current position with the position a given time interval ago. This time interval (or "window") can be adjusted using dhdConfigLinearVelocity, and should be modified to best suit the dynamic behavior of the device for a given application. The windowing estimator mode is the least resource intensive.
#define DHD_WRIST_ENC_0 3 |
Array index for encoder 0 of the WRIST structure (expert mode only).
#define DHD_WRIST_ENC_1 4 |
Array index for encoder 1 of the WRIST structure (expert mode only).
#define DHD_WRIST_ENC_2 5 |
Array index for encoder 2 of the WRIST structure (expert mode only).
#define DHD_WRIST_MOTOR_0 3 |
Array index for motor 0 of the WRIST structure (expert mode only).
#define DHD_WRIST_MOTOR_1 4 |
Array index for motor 1 of the WRIST structure (expert mode only).
#define DHD_WRIST_MOTOR_2 5 |
Array index for motor 2 of the WRIST structure (expert mode only).
enum dhd_errors |
See error management for more details on error management.
Enumerator | |
---|---|
DHD_NO_ERROR | No error occurred during processing. This is set as the default value in most of the SDK functions. |
DHD_ERROR | Undocumented error (for use by custom devices). |
DHD_ERROR_COM | There was a communication error between the current device controller and the host computer. |
DHD_ERROR_DHC_BUSY | The current device controller is busy and cannot perform the requested task. This error code does not apply to controllers that connect using the USB protocol. |
DHD_ERROR_NO_DRIVER_FOUND | A required device driver is not installed. Please refer to the user manual installation section. |
DHD_ERROR_NO_DEVICE_FOUND | No supported device was detected. |
DHD_ERROR_NOT_AVAILABLE | The command or feature is not available for the current device or in this SDK version. |
DHD_ERROR_TIMEOUT | The operation timed out. |
DHD_ERROR_GEOMETRY | One of the current device models (kinematic or force) reported an error. |
DHD_ERROR_EXPERT_MODE_DISABLED | The command or feature is not available because dhdEnableExpertMode() has not been called. |
DHD_ERROR_NOT_IMPLEMENTED | The command or feature is not implemented for the current device. |
DHD_ERROR_OUT_OF_MEMORY | Required memory could not be allocated. |
DHD_ERROR_DEVICE_NOT_READY | The current device is not ready to process the requested command. |
DHD_ERROR_FILE_NOT_FOUND | A required file is missing. |
DHD_ERROR_CONFIGURATION | There was an error trying to read the calibration data from the current device controller memory. |
DHD_ERROR_INVALID_INDEX | An index passed to the function is outside the expected valid range. |
DHD_ERROR_DEPRECATED | This feature, function or current device is marked deprecated. |
DHD_ERROR_NULL_ARGUMENT | The function producing this error was passed an unexpected null pointer argument. |
DHD_ERROR_REDUNDANT_FAIL | The redundant encoder integrity test failed. This error code only applies to devices with redundant encoders. |
DHD_ERROR_NOT_ENABLED | A feature is not enabled for the current device. |
DHD_ERROR_DEVICE_IN_USE | The current device is already in use by a function that requires exclusive access. |
DHD_ERROR_INVALID | The function producing this error was passed an invalid or unexpected argument. |
DHD_ERROR_NO_REGULATION | The robotic regulation thread is not running. This only applies to functions from the robotic SDK. |
int __SDK dhdCalibrateWrist | ( | char | ID | ) |
This function triggers the wrist calibration routine in the device controller.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdCheckControllerMemory | ( | char | ID | ) |
This function evaluates the integrity of the device controller firmware and internal configuration on supported device types.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdClose | ( | char | ID | ) |
This function closes the connection to a particular device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdConfigAngularVelocity | ( | int | ms, |
int | mode, | ||
char | ID | ||
) |
This function configures the internal velocity computation estimator. This only applies to the device wrist.
ms | [default=DHD_VELOCITY_WINDOW] time interval used to compute velocity [ms] |
mode | [default=DHD_VELOCITY_WINDOWING] device ID (see velocity estimator modes section for details) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdConfigGripperVelocity | ( | int | ms, |
int | mode, | ||
char | ID | ||
) |
This function configures the internal velocity computation estimator. This only applies to the device gripper.
ms | [default=DHD_VELOCITY_WINDOW] time interval used to compute velocity [ms] |
mode | [default=DHD_VELOCITY_WINDOWING] device ID (see velocity estimator modes section for details) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdConfigLinearVelocity | ( | int | ms, |
int | mode, | ||
char | ID | ||
) |
This function configures the internal velocity computation estimator. This only applies to the device base.
ms | [default=DHD_VELOCITY_WINDOW] time interval used to compute velocity [ms] |
mode | [default=DHD_VELOCITY_WINDOWING] device ID (see velocity estimator modes section for details) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdControllerSetDevice | ( | int | device, |
char | ID | ||
) |
If the connected device is a controller, this function lets the programmer define the Force Dimension mechanical structure attached to it. Upon selecting a device model, the routine will attempt to read that particular device configuration from the controller. If this fails, a default configuration will be selected and stored in the controller.
device | the device type to use |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaEncodersToJointAngles | ( | int | enc0, |
int | enc1, | ||
int | enc2, | ||
double * | j0, | ||
double * | j1, | ||
double * | j2, | ||
char | ID | ||
) |
This function computes and returns the delta joint angles for a given set of encoder readings.
enc0 | DELTA encoder reading on axis 0 |
enc1 | DELTA encoder reading on axis 1 |
enc2 | DELTA encoder reading on axis 2 |
j0 | [out] joint angle for axis 0 in [rad] |
j1 | [out] joint angle for axis 1 in [rad] |
j2 | [out] joint angle for axis 2 in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaEncoderToPosition | ( | int | enc0, |
int | enc1, | ||
int | enc2, | ||
double * | px, | ||
double * | py, | ||
double * | pz, | ||
char | ID | ||
) |
This function computes and returns the position of the end-effector for a given set of encoder readings.
enc0 | DELTA encoder reading on axis 0 |
enc1 | DELTA encoder reading on axis 1 |
enc2 | DELTA encoder reading on axis 2 |
px | [out] DELTA end-effector position on the X axis [m] |
py | [out] DELTA end-effector position on the Y axis [m] |
pz | [out] DELTA end-effector position on the Z axis [m] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaForceToMotor | ( | double | fx, |
double | fy, | ||
double | fz, | ||
int | enc0, | ||
int | enc1, | ||
int | enc2, | ||
ushort * | mot0, | ||
ushort * | mot1, | ||
ushort * | mot2, | ||
char | ID | ||
) |
This function computes and returns the motor commands necessary to obtain a given force on the end-effector at a given position (defined by encoder readings).
fx | force on the DELTA end-effector on the X axis [N] |
fy | force on the DELTA end-effector on the Y axis [N] |
fz | force on the DELTA end-effector on the Z axis [N] |
enc0 | DELTA encoder reading on axis 0 |
enc1 | DELTA encoder reading on axis 1 |
enc2 | DELTA encoder reading on axis 2 |
mot0 | [out] motor command on DELTA axis 0 |
mot1 | [out] motor command on DELTA axis 1 |
mot2 | [out] motor command on DELTA axis 2 |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaGravityJointTorques | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double * | q0, | ||
double * | q1, | ||
double * | q2, | ||
char | ID | ||
) |
This function computes the DELTA joint torques required to compensate for gravity in a given DELTA joint angle configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for axis 0 in [rad] |
j1 | joint angle for axis 1 in [rad] |
j2 | joint angle for axis 2 in [rad] |
q0 | out gravity compensation joint torque on axis 0 in [Nm] |
q1 | out gravity compensation joint torque on axis 1 in [Nm] |
q2 | out gravity compensation joint torque on axis 2 in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaJointAnglesToEncoders | ( | double | j0, |
double | j1, | ||
double | j2, | ||
int * | enc0, | ||
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
This function computes and returns the delta encoder readings for a given set of joint angles.
j0 | joint angle for axis 0 in [rad] |
j1 | joint angle for axis 1 in [rad] |
j2 | joint angle for axis 2 in [rad] |
enc0 | [out] DELTA encoder reading on axis 0 |
enc1 | [out] DELTA encoder reading on axis 1 |
enc2 | [out] DELTA encoder reading on axis 2 |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaJointAnglesToJacobian | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double | jcb[3][3], | ||
char | ID | ||
) |
This function retrieves the delta jacobian matrix based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for axis 0 in [rad] |
j1 | joint angle for axis 1 in [rad] |
j2 | joint angle for axis 2 in [rad] |
jcb | [out] device jacobian |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaJointTorquesExtrema | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double | minq[3], | ||
double | maxq[3], | ||
char | ID | ||
) |
This function computes the range of applicable DELTA joint torques for a given DELTA joint angle configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for axis 0 in [rad] |
j1 | joint angle for axis 1 in [rad] |
j2 | joint angle for axis 2 in [rad] |
minq | outarray of minimum applicable joint torque in [Nm] |
maxq | outarray of maximum applicable joint torque in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaMotorToForce | ( | ushort | mot0, |
ushort | mot1, | ||
ushort | mot2, | ||
int | enc0, | ||
int | enc1, | ||
int | enc2, | ||
double * | fx, | ||
double * | fy, | ||
double * | fz, | ||
char | ID | ||
) |
This function computes and returns the force applied to the end-effector for a given set of motor commands at a given position (defined by encoder readings).
mot0 | motor command on DELTA axis 0 |
mot1 | motor command on DELTA axis 1 |
mot2 | motor command on DELTA axis 2 |
enc0 | DELTA encoder reading on axis 0 |
enc1 | DELTA encoder reading on axis 1 |
enc2 | DELTA encoder reading on axis 2 |
fx | [out] force on the DELTA end-effector on the X axis [N] |
fy | [out] force on the DELTA end-effector on the Y axis [N] |
fz | [out] force on the DELTA end-effector on the Z axis [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDeltaPositionToEncoder | ( | double | px, |
double | py, | ||
double | pz, | ||
int * | enc0, | ||
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
This function computes and returns the encoder values for a given end-effector position.
px | DELTA end-effector position on the X axis [m] |
py | DELTA end-effector position on the Y axis [m] |
pz | DELTA end-effector position on the Z axis [m] |
enc0 | [out] DELTA encoder reading on axis 0 |
enc1 | [out] DELTA encoder reading on axis 1 |
enc2 | [out] DELTA encoder reading on axis 2 |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdDisableExpertMode | ( | ) |
This function disables the expert mode.
int __SDK dhdEmulateButton | ( | uchar | val, |
char | ID | ||
) |
This function enables the button behavior emulation in devices that feature a gripper.
val | DHD_ON to emulate button behavior, DHD_OFF to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdEnableExpertMode | ( | ) |
This function enables the expert mode.
int __SDK dhdEnableForce | ( | uchar | val, |
char | ID | ||
) |
This function enables the force mode in the device controller.
val | DHD_ON to enable force, DHD_OFF to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdEnableGripperForce | ( | uchar | val, |
char | ID | ||
) |
This function enables the gripper force mode in the device controller. This function is only relevant to devices that have a gripper with a default closed or opened state. It does not apply to the sigma.x and omega.x range of devices, whose gripper does not have a default state. For those devices, the gripper force is enabled/disabled by dhdEnableForce().
val | DHD_ON to enable gripper force, DHD_OFF to disable it |
ID | [default=-1] device ID (see multiple devices section for details) |
void __SDK dhdEnableSimulator | ( | bool | on | ) |
This function enables the device simulator support. This enables network access on the loopback interface.
on | true to enable, false to disable |
int __SDK dhdErrorGetLast | ( | ) |
Returns the last error code encountered in the running thread. See error management for details.
const char* __SDK dhdErrorGetLastStr | ( | ) |
Returns a brief string describing the last error encountered in the running thread. See error management for details.
const char* __SDK dhdErrorGetStr | ( | int | error | ) |
Returns a brief string describing a given error code. See error management for details.
error | error code |
int __SDK dhdGetAngularVelocityDeg | ( | double * | wx, |
double * | wy, | ||
double * | wz, | ||
char | ID | ||
) |
This function retrieves the estimated instantaneous angular velocity in [deg/s]. Velocity computation can be configured by calling dhdConfigAngularVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
wx | [out] angular velocity around the X axis [deg/s] |
wy | [out] angular velocity around the Y axis [deg/s] |
wz | [out] angular velocity around the Z axis [deg/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetAngularVelocityRad | ( | double * | wx, |
double * | wy, | ||
double * | wz, | ||
char | ID | ||
) |
This function retrieves the estimated instantaneous angular velocity in [rad/s]. Velocity computation can be configured by calling dhdConfigAngularVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
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] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetAvailableCount | ( | ) |
This function returns the number of available Force Dimension devices connected to the system. This encompasses all devices connected locally, but excludes devices already locked by other applications. Devices are given a unique identifier, as explained in the multiple devices section.
int __SDK dhdGetBaseAngleXDeg | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the X axis.
angle | [out] a pointer to a valid double to receive the device angle in [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetBaseAngleXRad | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the X axis.
angle | [out] a pointer to a valid double to receive the device angle in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetBaseAngleZDeg | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the vertical Z axis.
angle | [out] a pointer to a valid double to receive the device angle in [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetBaseAngleZRad | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the vertical Z axis.
angle | [out] a pointer to a valid double to receive the device angle in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetButton | ( | int | index, |
char | ID | ||
) |
This function returns the status of the button located on the end-effector.
index | button index, 0 for the gripper button (up to DHD_MAX_BUTTONS) |
ID | [default=-1] device ID (see multiple devices section for details) |
uint __SDK dhdGetButtonMask | ( | char | ID | ) |
This function returns the 32-bit binary mask of the device buttons.
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK dhdGetComFreq | ( | char | ID | ) |
This function returns the communication refresh rate between the computer and the device. Refresh rate computation is based on function calls that apply a force on the device (e.g. dhdSetForce()).
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetComMode | ( | char | ID | ) |
This function retrieves the COM operation mode on compatible devices.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetComponentVersionStr | ( | uint32_t | component, |
char * | buffer, | ||
size_t | size, | ||
char | ID | ||
) |
This function returns a string that describes an internal component version (if present).
component | Component ID provided by Force Dimension (device-specific). |
buffer | A user-allocated buffer to receive the component version string. |
size | The size of the user-allocated version string buffer. |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeltaEncoders | ( | int * | enc0, |
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
This function reads all encoders values of the DELTA structure.
enc0 | [out] DELTA axis 0 encoder reading |
enc1 | [out] DELTA axis 1 encoder reading |
enc2 | [out] DELTA axis 2 encoder reading |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeltaJacobian | ( | double | jacobian[3][3], |
char | ID | ||
) |
This function retrieves the jacobian matrix based on the current end-effector position. Please refer to your device user manual for more information on your device coordinate system.
jacobian | [out] device jacobian |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeltaJointAngles | ( | double * | j0, |
double * | j1, | ||
double * | j2, | ||
char | ID | ||
) |
This function retrieves the joint angles in [rad] for the DELTA structure.
j0 | [out] joint angle for axis 0 in [rad] |
j1 | [out] joint angle for axis 1 in [rad] |
j2 | [out] joint angle for axis 2 in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeviceAngleDeg | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the Y axis.
angle | [out] a pointer to a valid double to receive the device angle in [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeviceAngleRad | ( | double * | angle, |
char | ID | ||
) |
This function retrieves the device base plate angle around the Y axis.
angle | [out] a pointer to a valid double to receive the device angle in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetDeviceCount | ( | ) |
This function returns the number of compatible Force Dimension devices connected to the system. This encompasses all devices connected locally, including devices already locked by other applications. Devices are given a unique identifier, as explained in the multiple devices section.
int __SDK dhdGetDeviceID | ( | ) |
This function returns the ID of the current default device.
int __SDK dhdGetEffectorMass | ( | double * | mass, |
char | ID | ||
) |
This function retrieves the mass of the end-effector currently defined for a device. The gripper mass is used in the gravity compensation feature.
mass | a pointer to the actual end-effector mass in [kg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetEnc | ( | int | enc[DHD_MAX_DOF], |
uchar | mask, | ||
char | ID | ||
) |
This function retrieves encoder values into encoder array. It is particularly useful when using the the generic controller directly, without a device model attached.
enc | out encoder values array |
mask | [default=0xff] bitwise mask of which encoders should be read in |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetEncoder | ( | int | index, |
char | ID | ||
) |
This function reads a single encoder value from the haptic device.
index | the encoder index number as defined by DHD_MAX_DOF |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetEncRange | ( | int | encMin[DHD_MAX_DOF], |
int | encMax[DHD_MAX_DOF], | ||
char | ID | ||
) |
This function retrieves the expected min and max encoder values for all axis present on the current device. Axis indices that do not exist on the device will return a range of 0.
encMin | out minimum encoder values array |
encMax | out maximum encoder values array |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetEncVelocities | ( | double | v[DHD_MAX_DOF], |
char | ID | ||
) |
This function retrieves the encoder angle velocities in [increments/s] for all sensed degrees-of-freedom of the current device.
v | outarray of joint angle velocities in [rad/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetForce | ( | double * | fx, |
double * | fy, | ||
double * | fz, | ||
char | ID | ||
) |
This function retrieves the force vector applied to the end-effector.
fx | [out] force on the X axis in [N] |
fy | [out] force on the Y axis in [N] |
fz | [out] force on the Z axis in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetForceAndTorque | ( | double * | fx, |
double * | fy, | ||
double * | fz, | ||
double * | tx, | ||
double * | ty, | ||
double * | tz, | ||
char | ID | ||
) |
This function retrieves the force and torque vectors applied to the device end-effector.
fx | [out] force on the X axis in [N] |
fy | [out] force on the Y axis in [N] |
fz | [out] force on the Z axis in [N] |
tx | [out] torque around the X axis in [Nm] |
ty | [out] torque around the Y axis in [Nm] |
tz | [out] torque around the Z axis in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetForceAndTorqueAndGripperForce | ( | double * | fx, |
double * | fy, | ||
double * | fz, | ||
double * | tx, | ||
double * | ty, | ||
double * | tz, | ||
double * | f, | ||
char | ID | ||
) |
This function retrieves the force and torque vectors applied to the device end-effector, as well as the force applied to the gripper.
fx | [out] force on the X axis in [N] |
fy | [out] force on the Y axis in [N] |
fz | [out] force on the Z axis in [N] |
tx | [out] torque around the X axis in [Nm] |
ty | [out] torque around the Y axis in [Nm] |
tz | [out] torque around the Z axis in [Nm] |
f | [out] force on the gripper in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperAngleDeg | ( | double * | a, |
char | ID | ||
) |
This function retrieves the gripper opening angle in degrees.
a | [out] gripper opening [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperAngleRad | ( | double * | a, |
char | ID | ||
) |
This function retrieves the gripper opening angle in radians.
a | [out] gripper opening [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperAngularVelocityDeg | ( | double * | wg, |
char | ID | ||
) |
This function retrieves the estimated instantaneous angular velocity of the gripper in [deg/s]. Velocity computation can be configured by calling dhdConfigGripperVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
wg | [out] gripper angular velocity [deg/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperAngularVelocityRad | ( | double * | wg, |
char | ID | ||
) |
This function retrieves the estimated instantaneous angular velocity of the gripper in [rad/s]. Velocity computation can be configured by calling dhdConfigGripperVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
wg | [out] gripper angular velocity [rad/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperEncoder | ( | int * | enc, |
char | ID | ||
) |
This function retrieves the encoder value of the force gripper.
enc | [out] gripper encoder reading |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperFingerPos | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
char | ID | ||
) |
This function retrieves the position in Cartesian coordinates of forefinger rest location of the force gripper structure if present.
px | [out] gripper finger X coord |
py | [out] gripper finger Y coord |
pz | [out] gripper finger Z coord |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperGap | ( | double * | g, |
char | ID | ||
) |
This function retrieves the gripper opening distance in meters.
g | [out] gripper opening [m] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperLinearVelocity | ( | double * | vg, |
char | ID | ||
) |
This function retrieves the estimated instantaneous linear velocity of the gripper in [m/s]. Velocity computation can be configured by calling dhdConfigGripperVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
vg | [out] gripper linear velocity [m/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetGripperThumbPos | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
char | ID | ||
) |
This function retrieves the position in Cartesian coordinates of thumb rest location of the force gripper structure if present.
px | [out] gripper thumb X coord |
py | [out] gripper thumb Y coord |
pz | [out] gripper thumb Z coord |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetJointAngleRange | ( | double | jmin[DHD_MAX_DOF], |
double | jmax[DHD_MAX_DOF], | ||
char | ID | ||
) |
This function retrieves the expected min and max joint angles in [rad] for all sensed degrees-of-freedom on the current device. Axis indices that do not exist on the device will return a range of 0.0.
jmin | outarray of min joint angles in [rad] |
jmax | outarray of max joint angles in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetJointAngles | ( | double | j[DHD_MAX_DOF], |
char | ID | ||
) |
This function retrieves the joint angles in [rad] for all sensed degrees-of-freedom of the current device.
j | outarray of joint angles in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetJointVelocities | ( | double | v[DHD_MAX_DOF], |
char | ID | ||
) |
This function retrieves the joint angle velocities in [rad/s] for all sensed degrees-of-freedom of the current device.
v | outarray of joint angle velocities in [rad/s] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetLinearVelocity | ( | double * | vx, |
double * | vy, | ||
double * | vz, | ||
char | ID | ||
) |
This function retrieves the estimated instantaneous translational velocity. Velocity computation can be configured by calling dhdConfigLinearVelocity(). By default DHD_VELOCITY_WINDOW and DHD_VELOCITY_WINDOWING are used. See velocity estimator for details.
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] |
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK dhdGetMaxForce | ( | char | ID | ) |
This function retrieves the current limit (in N) to the force magnitude that can be applied by the haptic device. If the return value is negative, the limit is disabled and the full range of force available can be applied.
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK dhdGetMaxGripperForce | ( | char | ID | ) |
This function retrieves the current limit (in N) to the force magnitude that can be applied by the haptic device gripper. If the return value is negative, the limit is disabled and the full range of gripper force available can be applied.
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK dhdGetMaxTorque | ( | char | ID | ) |
This function retrieves the current limit (in Nm) to the torque magnitude that can be applied by the haptic device. If the return value is negative, the limit is disabled and the full range of torque available can be applied.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetOrientationDeg | ( | double * | oa, |
double * | ob, | ||
double * | og, | ||
char | ID | ||
) |
For devices with a wrist structure, This function retrieves individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. Please refer to your device user manual for more information on your device coordinate system.
oa | [out] device orientation around the first wrist joint in [deg] |
ob | [out] device orientation around the second wrist joint in [deg] |
og | [out] device orientation around the third wrist joint in [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetOrientationFrame | ( | double | matrix[3][3], |
char | ID | ||
) |
This function retrieves the rotation matrix of the wrist structure. The identity matrix is returned for devices that do not support orientations.
matrix | [out] orientation matrix frame |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetOrientationRad | ( | double * | oa, |
double * | ob, | ||
double * | og, | ||
char | ID | ||
) |
For devices with a wrist structure, this function retrieves individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. Please refer to your device user manual for more information on your device coordinate system.
oa | [out] device orientation around the first wrist joint in [rad] |
ob | [out] device orientation around the second wrist joint in [rad] |
og | [out] device orientation around the third wrist joint in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetPosition | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
char | ID | ||
) |
This function retrieves 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] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetPositionAndOrientationDeg | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
double * | oa, | ||
double * | ob, | ||
double * | og, | ||
char | ID | ||
) |
This function retrieves the position and orientation of the end-effector in Cartesian coordinates. For devices with a wrist structure, the orientation is expressed as the individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. 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 wrist joint in [deg] |
ob | [out] device orientation around the second wrist joint in [deg] |
og | [out] device orientation around the thrid wrist joint in [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetPositionAndOrientationFrame | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
double | matrix[3][3], | ||
char | ID | ||
) |
This function retrieves the position and orientation matrix 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] |
matrix | [out] orientation matrix frame |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetPositionAndOrientationRad | ( | double * | px, |
double * | py, | ||
double * | pz, | ||
double * | oa, | ||
double * | ob, | ||
double * | og, | ||
char | ID | ||
) |
This function retrieves the position and orientation of the end-effector in Cartesian coordinates. For devices with a wrist structure, the orientation is expressed as the individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. 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 wrist joint in [rad] |
ob | [out] device orientation around the second wrist joint in [rad] |
og | [out] device orientation around the third wrist joint in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
void __SDK dhdGetSDKVersion | ( | int * | major, |
int * | minor, | ||
int * | release, | ||
int * | revision | ||
) |
This function returns the SDK complete set of version numbers.
major | major version number |
minor | minor version number |
release | release number |
revision | revision number |
const char* __SDK dhdGetSDKVersionStr | ( | ) |
This function returns a string that fully describes the SDK version.
int __SDK dhdGetSerialNumber | ( | ushort * | sn, |
char | ID | ||
) |
This function returns the device serial number.
sn | [out] a pointer to a valid unsigned char to receive the device serial number |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetStatus | ( | int | status[DHD_MAX_STATUS], |
char | ID | ||
) |
This function returns the status vector of the haptic device. The status is described in the status section.
status | [out] an array that will receive the status vector |
ID | [default=-1] device ID (see multiple devices section for details) |
ulong __SDK dhdGetSystemCounter | ( | ) |
This function returns a timestamp computed from the high-resolution system counter, expressed in microseconds. This function is deprecated, please use dhdGetTime() instead.
const char* __SDK dhdGetSystemName | ( | char | ID | ) |
This function returns the haptic device type. As this SDK can be used to control all of Force Dimension haptic products, this can help programmers ensure that their application is running on the appropriate target haptic device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetSystemRev | ( | char | ID | ) |
This function returns the revision associated with this instance of haptic device type. As this SDK can be used to control all of Force Dimension haptic products, this can help programmers ensure that their application is running on the appropriate target haptic device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetSystemType | ( | char | ID | ) |
This function returns the haptic device type. As this SDK can be used to control all of Force Dimension haptic products, this can help programmers ensure that their application is running on the appropriate target haptic device.
ID | [default=-1] device ID (see multiple devices section for details) |
double __SDK dhdGetTime | ( | ) |
This function returns the current value from the high-resolution system counter in [s]. The resolution of the system counter may be machine-dependent, as it is usually derived from one of the CPU clocks signals. The time returned is guaranteed to be monotonic.
int __SDK dhdGetVelocityThreshold | ( | uint * | val, |
char | ID | ||
) |
This function retrieves the current velocity threshold of the device. Velocity threshold is a safety feature that prevents the device from accelerating to high velocities without control. If the velocity of one of the device axis passes the threshold, the device enters BRAKES mode.
val | an arbitrary value of velocity threshold the range of threshold values is device dependent, it is recommended NOT to modify factory settings |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetVersion | ( | double * | ver, |
char | ID | ||
) |
This function returns the device controller version. As this SDK can be used to control all of Force Dimension haptic products, this can help programmers ensure that their application is running on the appropriate version of the haptic controller.
ver | [out] pointer to a variable that will receive the controller release version number |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetVersionStr | ( | char * | buffer, |
size_t | size, | ||
char | ID | ||
) |
This function returns the device controller version string. As this SDK can be used to control all of Force Dimension haptic products, this can help programmers ensure that their application is running on the appropriate version of the haptic controller.
buffer | A user-allocated buffer to receive the device controller version string. |
size | The size of the user-allocated version string buffer. |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetWatchdog | ( | uchar * | val, |
char | ID | ||
) |
This function retrieves the watchdog duration in multiples of 125 microseconds on compatible devices.
val | [out]watchdog duration in multiples of 125 [us] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetWristEncoders | ( | int * | enc0, |
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
This function reads the encoders values of the wrist structure.
enc0 | [out] wrist joint 0 encoder reading |
enc1 | [out] wrist joint 1 encoder reading |
enc2 | [out] wrist joint 2 encoder reading |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetWristJacobian | ( | double | jacobian[3][3], |
char | ID | ||
) |
This function retrieves the wrist jacobian matrix based on the current end-effector position. Please refer to your device user manual for more information on your device coordinate system.
jacobian | [out] device jacobian |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGetWristJointAngles | ( | double * | j0, |
double * | j1, | ||
double * | j2, | ||
char | ID | ||
) |
This function retrieves the joint angles in [rad] for the wrist structure.
j0 | [out] joint angle for joint 0 in [rad] |
j1 | [out] joint angle for joint 1 in [rad] |
j2 | [out] joint angle for joint 2 in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperAngleRadToEncoder | ( | double | a, |
int * | enc, | ||
char | ID | ||
) |
This function computes and returns the gripper encoder value for a given gripper angle in [rad]
a | gripper opening in [rad] |
enc | [out] gripper encoder reading |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperEncoderToAngleRad | ( | int | enc, |
double * | a, | ||
char | ID | ||
) |
This function computes and returns the opening of the gripper as an angle in [rad] for a given encoder reading.
enc | gripper encoder reading |
a | [out] gripper opening [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperEncoderToGap | ( | int | enc, |
double * | gap, | ||
char | ID | ||
) |
This function computes and returns the opening of the gripper as a distance in [m] for a given encoder reading.
enc | gripper encoder reading |
gap | [out] gripper opening [m] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperForceToMotor | ( | double | frc, |
ushort * | mot, | ||
int | enc[4], | ||
char | ID | ||
) |
Given a desired force to be displayed by the force gripper, this function computes and returns the corresponding motor command.
frc | force on the gripper end-effector [N] |
mot | [out] motor command on gripper axis |
enc | encoder reading for wrist (at indices 0,1,2) and gripper (at index 3) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperGapToEncoder | ( | double | gap, |
int * | enc, | ||
char | ID | ||
) |
This function computes and returns the gripper encoder value for a given gripper opening distance in [m]
gap | gripper opening in [m] |
enc | [out] gripper encoder reading |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdGripperMotorToForce | ( | ushort | mot, |
double * | frc, | ||
int | enc[4], | ||
char | ID | ||
) |
This function computes and returns the force applied to the end-effector for a given motor command.
mot | motor command on gripper axis |
frc | [out] force on the gripper end-effector [N] |
enc | encoder reading for wrist (at indices 0,1,2) and gripper (at index 3) |
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdHasActiveGripper | ( | char | ID | ) |
This function returns true if the device has an active gripper, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdHasActiveWrist | ( | char | ID | ) |
This function returns true if the device has an active wrist, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdHasBase | ( | char | ID | ) |
This function returns true if the device has a base, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdHasGripper | ( | char | ID | ) |
This function returns true if the device has a gripper, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdHasWrist | ( | char | ID | ) |
This function returns true if the device has a wrist, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
bool __SDK dhdIsLeftHanded | ( | char | ID | ) |
This function returns true if the device is configured for left-handed use, false otherwise.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdJointAnglesToInertiaMatrix | ( | double | j[DHD_MAX_DOF], |
double | inertia[6][6], | ||
char | ID | ||
) |
This function retrieves the (Cartesian) inertia matrix based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.
j | array of joint angles in [rad] |
inertia | [out] device inertia matrix |
ID | [default=-1] device ID (see multiple devices section for details) |
char __SDK dhdKbGet | ( | ) |
This function retrieves a character from the keyboard (OS independent).
bool __SDK dhdKbHit | ( | ) |
This function checks the keyboard for a key hit (OS independent).
int __SDK dhdOpen | ( | ) |
This function opens a connection to the first available device connected to the system. The order in which devices are opened persists until devices are added or removed.
int __SDK dhdOpenID | ( | char | index | ) |
This function opens a connection to one particular 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 dhdOpenSerial | ( | int | serial | ) |
This function opens a connection to the device with a given serial number (available on recent models only).
serial | requested system serial number |
int __SDK dhdOpenType | ( | int | type | ) |
This function opens a connection to the first device of a given type connected to the system. The order in which devices are opened persists until devices are added or removed.
type | requested system Device Types type |
int __SDK dhdPreloadMot | ( | ushort | mot[DHD_MAX_DOF], |
uchar | mask, | ||
char | ID | ||
) |
This function programs motor commands to a selection of motor channels. Unlike dhdSetMot(), this function saves the requested commands internally for later application by calling dhdSetForce() and the likes.
mot | motor values array |
mask | [default=0xff] bitwise mask of which motor should be set |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdPreset | ( | int | val[DHD_MAX_DOF], |
uchar | mask, | ||
char | ID | ||
) |
This function sets selected encoder offsets to a given value. Intended for use with the the generic controller when no RESET button is available.
val | motor values array |
mask | bitwise mask of which encoder should be set |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdReadConfigFromFile | ( | char * | filename, |
char | ID | ||
) |
This function loads a specific device calibration/configuration data from a file. Particularly useful when using the generic controller connected to a Force Dimension device without using the dhdControllerSetDevice() call.
filename | configuration file |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdReset | ( | char | ID | ) |
This function puts the device in RESET mode.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdResetWrist | ( | char | ID | ) |
This function resets the wrist calibration on a delta.6 haptic device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBaseAngleXDeg | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the X axis. Please refer to your device user manual for more information on your device coordinate system.
angle | device base plate angle around X [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBaseAngleXRad | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the X axis. Please refer to your device user manual for more information on your device coordinate system.
angle | device base plate angle around X [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBaseAngleZDeg | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the vertical Z axis. Please refer to your device user manual for more information on your device coordinate system.
angle | device base plate angle around Z [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBaseAngleZRad | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the vertical Z axis. Please refer to your device user manual for more information on your device coordinate system.
angle | device base plate angle around Z [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBrakes | ( | int | val, |
char | ID | ||
) |
This function toggles the device electromagnetic brakes state.
val | desired state of the brakes (DHD_ON or DHD_OFF) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetBrk | ( | uchar | mask, |
char | ID | ||
) |
This function sets brakes electromagnetic brakes status on selective motor groups. Only applies when using the generic controller directly, without a device model attached.
mask | [default=0xff] bitwise mask of which motor group should the brakes be set on. |
ID | [default=-1] device ID (see multiple devices section for details) |
mask
argument addresses all 8 motors bitwise. I a single bit within a motor group address is enabled, the entire motor group dhd_brakes will be activated.int __SDK dhdSetComMode | ( | int | mode, |
char | ID | ||
) |
This function sets the COM operation mode on compatible devices.
mode | desired COM operation mode |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetComModePriority | ( | int | priority, |
char | ID | ||
) |
This function sets the priority of the thread (if any) that supports the current COM operation mode on compatible devices. Currently unused.
priority | desired thread priority |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetDeltaJointTorques | ( | double | t0, |
double | t1, | ||
double | t2, | ||
char | ID | ||
) |
This function sets all joint torques of the DELTA structure.
t0 | DELTA axis 0 torque command [Nm] |
t1 | DELTA axis 1 torque command [Nm] |
t2 | DELTA axis 2 torque command [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetDeltaMotor | ( | ushort | mot0, |
ushort | mot1, | ||
ushort | mot2, | ||
char | ID | ||
) |
This function sets desired motor commands to the amplifier channels commanding the DELTA motors.
mot0 | DELTA axis 0 motor command |
mot1 | DELTA axis 1 motor command |
mot2 | DELTA axis 2 motor command |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetDevice | ( | char | ID | ) |
This function selects the default device that will receive the SDK commands. The SDK supports multiple devices. This routine allows the programmer to decide which device the SDK dhd_single_device_call single-device calls will address. Any subsequent SDK 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 dhdSetDeviceAngleDeg | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the (inverted) Y axis. Please refer to your device user manual for more information on your device coordinate system. An angle value of 0 corresponds to the device "upright" position, with its base plate perpendicular to axis X. An angle value of 90 corresponds to the device base plate resting horizontally.
angle | device base plate angle [deg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetDeviceAngleRad | ( | double | angle, |
char | ID | ||
) |
This function sets the device base plate angle around the (inverted) Y axis. Please refer to your device user manual for more information on your device coordinate system. An angle value of 0 corresponds to the device "upright" position, with its base plate perpendicular to axis X. An angle value of Pi/2 corresponds to the device base plate resting horizontally.
angle | device base plate angle [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetEffectorMass | ( | double | mass, |
char | ID | ||
) |
This function defines the mass of the end-effector. This function is required to provide accurate gravity compensation when custom-made or modified end-effectors are used.
mass | the actual end-effector mass in [kg] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetForce | ( | double | fx, |
double | fy, | ||
double | fz, | ||
char | ID | ||
) |
This function sets the desired force vector in Cartesian coordinates to be applied to the end-effector of the device.
fx | force on the X axis in [N] |
fy | force on the Y axis in [N] |
fz | force on the Z axis in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetForceAndGripperForce | ( | double | fx, |
double | fy, | ||
double | fz, | ||
double | fg, | ||
char | ID | ||
) |
This function sets the desired force vector in Cartesian coordinates and the desired grasping force to be applied to the device end-effector and force gripper.
fx | translation force along X axis |
fy | translation force along Y axis |
fz | translation force along Z axis |
fg | grasping force |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetForceAndTorque | ( | double | fx, |
double | fy, | ||
double | fz, | ||
double | tx, | ||
double | ty, | ||
double | tz, | ||
char | ID | ||
) |
This function sets the desired force and torque vectors to be applied to the device end-effector.
fx | force on the X axis in [N] |
fy | force on the Y axis in [N] |
fz | force on the Z axis in [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] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetForceAndTorqueAndGripperForce | ( | double | fx, |
double | fy, | ||
double | fz, | ||
double | tx, | ||
double | ty, | ||
double | tz, | ||
double | fg, | ||
char | ID | ||
) |
This function sets the desired force and torque vectors in Cartesian coordinates and the desired grasping force to be applied to the device end-effector and force gripper.
fx | force on the X axis in [N] |
fy | force on the Y axis in [N] |
fz | force on the Z axis in [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 dhdSetForceAndWristJointTorques | ( | double | fx, |
double | fy, | ||
double | fz, | ||
double | t0, | ||
double | t1, | ||
double | t2, | ||
char | ID | ||
) |
This function sets Cartesian force and wrist joint torques.
fx | translation force along X axis [N] |
fy | translation force along Y axis [N] |
fz | translation force along Z axis [N] |
t0 | wrist joint 0 torque command [Nm] |
t1 | wrist joint 1 torque command [Nm] |
t2 | wrist joint 2 torque command [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetForceAndWristJointTorquesAndGripperForce | ( | double | fx, |
double | fy, | ||
double | fz, | ||
double | t0, | ||
double | t1, | ||
double | t2, | ||
double | fg, | ||
char | ID | ||
) |
This function sets Cartesian force, wrist joint torques and gripper force.
fx | translation force along X axis [N] |
fy | translation force along Y axis [N] |
fz | translation force along Z axis [N] |
t0 | wrist joint 0 torque command [Nm] |
t1 | wrist joint 1 torque command [Nm] |
t2 | wrist joint 2 torque command [Nm] |
fg | gripper force [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetGravityCompensation | ( | int | val, |
char | ID | ||
) |
This function toggles the use of the gravity compensation feature.
val | desired state of the gravity compensation feature (DHD_ON or DHD_OFF) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetGripperMotor | ( | ushort | mot, |
char | ID | ||
) |
This function sets a desired motor command to the force gripper.
mot | gripper motor command |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetMaxForce | ( | double | f, |
char | ID | ||
) |
This function defines a limit (in N) to the force magnitude that can be applied by the haptic device. The f
N limit applies to all dhdSetForce() and related calls, and ensures that the force applied to the device end-effector remains below the requested value. If the f
argument is negative, the limit is disabled and the full range of force available can be applied.
f | the maximum force that can be displayed by the device in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetMaxGripperForce | ( | double | f, |
char | ID | ||
) |
This function defines a limit (in N) to the force magnitude that can be applied by the haptic device gripper. The f
N limit applies to dhdSetForceAndTorqueAndGripperForce() and related calls, and ensures that the force applied to the device gripper remains below the requested value. If the f
argument is negative, the limit is disabled and the full range of gripper force available can be applied.
f | the maximum force that can be displayed by the device gripper in [N] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetMaxTorque | ( | double | t, |
char | ID | ||
) |
This function defines a limit (in Nm) to the torque magnitude that can be applied by the haptic device. The t
Nm limit applies to all dhdSetForceAndTorque() and related calls, and ensures that the torque applied to the device end-effector remains below the requested value. If the t
argument is negative, the limit is disabled and the full range of torque available can be applied.
t | the maximum torque that can be displayed by the device in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetMot | ( | ushort | mot[DHD_MAX_DOF], |
uchar | mask, | ||
char | ID | ||
) |
This function programs motor commands to a selection of motor channels. Particularly useful when using the generic controller directly, without a device model attached.
mot | motor values array |
mask | [default=0xff] bitwise mask of which motor should be set |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetMotor | ( | int | index, |
ushort | val, | ||
char | ID | ||
) |
This function programs a command to a single motor channel.
index | the motor index number as defined by DHD_MAX_DOF |
val | the motor DAC value |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetOutput | ( | uint | output, |
char | ID | ||
) |
This function sets the user programmable output bits on devices that support it.
output | a bitwise mask that toggles the programmable output bits |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetStandardGravity | ( | double | g, |
char | ID | ||
) |
This function sets the standard gravity constant used in gravity compensation. By default, the constant is set to 9.81 m/s^2.
g | standard gravity constant [m/s^2] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetTimeGuard | ( | int | us, |
char | ID | ||
) |
This function toggles the use of the TimeGuard feature with an arbitrary minimum period.
us | minimum refresh period in [us] a value of 0 disables the TimeGuard feature, while a value of -1 resets the default value (recommended) |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetVelocityThreshold | ( | uint | val, |
char | ID | ||
) |
This function adjusts the velocity threshold of the device. Velocity threshold is a safety feature that prevents the device from accelerating to high velocities without control. If the velocity of one of the device axis passes the threshold, the device enters BRAKES mode.
val | an arbitrary value of velocity threshold the range of threshold values is device dependent, it is recommended NOT to modify factory settings |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetVibration | ( | double | freq, |
double | amplitude, | ||
int | type, | ||
char | ID | ||
) |
This function applies a vibration to the end-effector. The vibration is added to the force requested by dhdSetForce() and the like. The vibration application mechanism depends on the specific device type, and is currently only available on devices with dedicated vibration actuators.
freq | Vibration frequency in Hz |
amplitude | Vibration amplitude in N |
type | Vibration profile (unused, reserved for future use) |
ID | [default=-1] Device ID (see multiple devices section for details) |
int __SDK dhdSetWatchdog | ( | uchar | val, |
char | ID | ||
) |
This function sets the watchdog duration in multiples of 125 microseconds on compatible devices. If the watchdog duration is exceeded before the device receives a new force command, the device firmware will disable forces. A value of 0 disables the watchdog feature.
val | watchdog duration in multiples of 125 [us] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetWristJointTorques | ( | double | t0, |
double | t1, | ||
double | t2, | ||
char | ID | ||
) |
This function sets all joint torques of the wrist structure.
t0 | wrist joint 0 torque command [Nm] |
t1 | wrist joint 1 torque command [Nm] |
t2 | wrist joint 2 torque command [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdSetWristMotor | ( | ushort | mot0, |
ushort | mot1, | ||
ushort | mot2, | ||
char | ID | ||
) |
This function sets desired motor commands to the amplifier channels commanding the wrist motors.
mot0 | wrist joint 0 motor command |
mot1 | wrist joint 1 motor command |
mot2 | wrist joint 2 motor command |
ID | [default=-1] device ID (see multiple devices section for details) |
void __SDK dhdSleep | ( | double | sec | ) |
This function sleeps for a given period of time (OS independent).
sec | sleep period in [s] |
int __SDK dhdStartThread | ( | void * | funcvoid *, |
void * | arg, | ||
int | priority | ||
) |
This function creates a thread on any operating systems supported by the SDK.
func | function to run in the thread |
arg | optional pointer to an argument passed to the thread function |
priority | priority given to the thread (see the multi-threading section for details). The SDK will try to set the priority level, but will continue without error if the OS does not accept the request. |
int __SDK dhdStop | ( | char | ID | ) |
This function stops all forces on the device. This routine disables the force on the haptic device and puts it into BRAKE mode.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdUpdateEncoders | ( | char | ID | ) |
This function forces an update of the internal encoder values in the state vector. This call retrieves the encoder readings from the device and places them into the state vector. No kinematic model is called.
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWaitForReset | ( | int | timeout, |
char | ID | ||
) |
This function puts the device in RESET mode and wait for the user to calibrate the device. Optionally, a timeout can be defined after which the call returns even if calibration has not occurred.
timeout | [optional] maximum time to wait for calibration in [ms] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristEncodersToJointAngles | ( | int | enc0, |
int | enc1, | ||
int | enc2, | ||
double * | j0, | ||
double * | j1, | ||
double * | j2, | ||
char | ID | ||
) |
This function computes and returns the wrist joint angles for a given set of encoder readings.
enc0 | wrist encoder reading on axis 0 |
enc1 | wrist encoder reading on axis 1 |
enc2 | wrist encoder reading on axis 2 |
j0 | [out] joint angle for wrist axis 0 in [rad] |
j1 | [out] joint angle for wrist axis 1 in [rad] |
j2 | [out] joint angle for wrist axis 2 in [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristEncoderToOrientation | ( | int | enc0, |
int | enc1, | ||
int | enc2, | ||
double * | oa, | ||
double * | ob, | ||
double * | og, | ||
char | ID | ||
) |
For devices with a wrist structure, this function computes individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. Please refer to your device user manual for more information on your device coordinate system.
enc0 | wrist encoder reading on axis 0 |
enc1 | wrist encoder reading on axis 1 |
enc2 | wrist encoder reading on axis 2 |
oa | [out] wrist end-effector orientation around the first wrist joint [rad] |
ob | [out] wrist end-effector orientation around the second wrist joint [rad] |
og | [out] wrist end-effector orientation around the third wrist joint [rad] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristGravityJointTorques | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double * | q0, | ||
double * | q1, | ||
double * | q2, | ||
char | ID | ||
) |
This function computes the wrist joint torques required to compensate for gravity in a given wrist joint angle configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for wrist axis 0 in [rad] |
j1 | joint angle for wrist axis 1 in [rad] |
j2 | joint angle for wrist axis 2 in [rad] |
q0 | out gravity compensation joint torque on axis 0 in [Nm] |
q1 | out gravity compensation joint torque on axis 1 in [Nm] |
q2 | out gravity compensation joint torque on axis 2 in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristJointAnglesToEncoders | ( | double | j0, |
double | j1, | ||
double | j2, | ||
int * | enc0, | ||
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
This function computes and returns the wrist encoder readings for a given set of joint angles.
j0 | joint angle for axis 0 in [rad] |
j1 | joint angle for axis 1 in [rad] |
j2 | joint angle for axis 2 in [rad] |
enc0 | [out] wrist encoder reading on axis 0 |
enc1 | [out] wrist encoder reading on axis 1 |
enc2 | [out] wrist encoder reading on axis 2 |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristJointAnglesToJacobian | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double | jcb[3][3], | ||
char | ID | ||
) |
This function retrieves the wrist jacobian matrix based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for wrist axis 0 in [rad] |
j1 | joint angle for wrist axis 1 in [rad] |
j2 | joint angle for wrist axis 2 in [rad] |
jcb | [out] device jacobian |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristJointTorquesExtrema | ( | double | j0, |
double | j1, | ||
double | j2, | ||
double | minq[3], | ||
double | maxq[3], | ||
char | ID | ||
) |
This function computes the range of applicable wrist joint torques for a given wrist joint angle configuration. Please refer to your device user manual for more information on your device coordinate system.
j0 | joint angle for wrist axis 0 in [rad] |
j1 | joint angle for wrist axis 1 in [rad] |
j2 | joint angle for wrist axis 2 in [rad] |
minq | outarray of minimum applicable joint torque in [Nm] |
maxq | outarray of maximum applicable joint torque in [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristMotorToTorque | ( | ushort | mot0, |
ushort | mot1, | ||
ushort | mot2, | ||
int | enc0, | ||
int | enc1, | ||
int | enc2, | ||
double * | tx, | ||
double * | ty, | ||
double * | tz, | ||
char | ID | ||
) |
This function computes and returns the torque applied to the end-effector for a given set of motor commands at a given orientation (defined by encoder readings).
mot0 | motor command around wrist joint 0 |
mot1 | motor command around wrist joint 1 |
mot2 | motor command around wrist joint 2 |
enc0 | wrist encoder reading around axis 0 |
enc1 | wrist encoder reading around axis 1 |
enc2 | wrist encoder reading around axis 2 |
tx | [out] torque on the wrist end-effector around the X axis [Nm] |
ty | [out] torque on the wrist end-effector around the Y axis [Nm] |
tz | [out] torque on the wrist end-effector around the Z axis [Nm] |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristOrientationToEncoder | ( | double | oa, |
double | ob, | ||
double | og, | ||
int * | enc0, | ||
int * | enc1, | ||
int * | enc2, | ||
char | ID | ||
) |
For devices with a wrist structure, this function computes the encoder values from individual angle of each joint, starting with the one located nearest to the wrist base plate. For the DHD_DEVICE_OMEGA33 and DHD_DEVICE_OMEGA33_LEFT devices, angles must be expressed with respect to their internal reference frame, which is rotated 45 degrees around the Y axis. Please refer to your device user manual for more information on your device coordinate system.
oa | wrist end-effector orientation around the X axis [rad] |
ob | wrist end-effector orientation around the Y axis [rad] |
og | wrist end-effector orientation around the Z axis [rad] |
enc0 | [out] wrist encoder reading on first joint |
enc1 | [out] wrist encoder reading on second joint |
enc2 | [out] wrist encoder reading on third joint |
ID | [default=-1] device ID (see multiple devices section for details) |
int __SDK dhdWristTorqueToMotor | ( | double | tx, |
double | ty, | ||
double | tz, | ||
int | enc0, | ||
int | enc1, | ||
int | enc2, | ||
ushort * | mot0, | ||
ushort * | mot1, | ||
ushort * | mot2, | ||
char | ID | ||
) |
This function computes and returns the motor command necessary to obtain a given torque on the end-effector at a given orientation (defined by encoder readings).
tx | torque on the wrist end-effector around the X axis [Nm] |
ty | torque on the wrist end-effector around the Y axis [Nm] |
tz | torque on the wrist end-effector around the Z axis [Nm] |
enc0 | wrist encoder reading on axis 0 |
enc1 | wrist encoder reading on axis 1 |
enc2 | wrist encoder reading on axis 2 |
mot0 | [out] motor command around wrist joint 0 |
mot1 | [out] motor command around wrist joint 1 |
mot2 | [out] motor command around wrist joint 2 |
ID | [default=-1] device ID (see multiple devices section for details) |