DHD header file. More...
Defines | |
#define | DHD_DEVICE_NONE 0 |
#define | DHD_DEVICE_3DOF 31 |
#define | DHD_DEVICE_6DOF 61 |
#define | DHD_DEVICE_6DOF_500 62 |
#define | DHD_DEVICE_3DOF_USB 63 |
#define | DHD_DEVICE_6DOF_USB 64 |
#define | DHD_DEVICE_OMEGA 32 |
#define | DHD_DEVICE_OMEGA3 33 |
#define | DHD_DEVICE_OMEGA33 34 |
#define | DHD_DEVICE_OMEGA33_LEFT 36 |
#define | DHD_DEVICE_OMEGA331 35 |
#define | DHD_DEVICE_OMEGA331_LEFT 37 |
#define | DHD_DEVICE_CONTROLLER 81 |
#define | DHD_DEVICE_CONTROLLER_HR 82 |
#define | DHD_DEVICE_CUSTOM 91 |
#define | DHD_ON 1 |
#define | DHD_OFF 0 |
#define | DHD_MAX_DEVICE 4 |
#define | DHD_MAX_ENC 8 |
#define | DHD_MAX_MOTOR 6 |
#define | DHD_DELTA_MOTOR_0 0 |
#define | DHD_DELTA_MOTOR_1 1 |
#define | DHD_DELTA_MOTOR_2 2 |
#define | DHD_DELTA_ENC_0 0 |
#define | DHD_DELTA_ENC_1 1 |
#define | DHD_DELTA_ENC_2 2 |
#define | DHD_WRIST_MOTOR_0 3 |
#define | DHD_WRIST_MOTOR_1 4 |
#define | DHD_WRIST_MOTOR_2 5 |
#define | DHD_WRIST_ENC_0 3 |
#define | DHD_WRIST_ENC_1 4 |
#define | DHD_WRIST_ENC_2 5 |
#define | DHD_TIMEGUARD 1 |
#define | DHD_MAX_STATUS 13 |
#define | DHD_STATUS_POWER 0 |
#define | DHD_STATUS_CONNECTED 1 |
#define | DHD_STATUS_STARTED 2 |
#define | DHD_STATUS_RESET 3 |
#define | DHD_STATUS_IDLE 4 |
#define | DHD_STATUS_FORCE 5 |
#define | DHD_STATUS_BRAKE 6 |
#define | DHD_STATUS_TORQUE 7 |
#define | DHD_STATUS_WRIST_DETECTED 8 |
#define | DHD_STATUS_ERROR 9 |
#define | DHD_STATUS_GRAVITY 10 |
#define | DHD_STATUS_TIMEGUARD 11 |
#define | DHD_MAX_BUTTONS 8 |
#define | DHD_VELOCITY_WINDOWING 0 |
#define | DHD_VELOCITY_AVERAGING 1 |
Enumerations | |
enum | dhd_errors { DHD_NO_ERROR, DHD_ERROR, DHD_ERROR_COM, DHD_ERROR_DHC_BUSY, DHD_ERROR_NO_DRIVER_FOUND, DHD_ERROR_NO_DEVICE_FOUND, DHD_ERROR_NOT_AVAILABLE, DHD_ERROR_TIMEOUT, DHD_ERROR_GEOMETRY, DHD_ERROR_EXPERT_MODE_DISABLED, DHD_ERROR_NOT_IMPLEMENTED, DHD_ERROR_OUT_OF_MEMORY, DHD_ERROR_DEVICE_NOT_READY, DHD_ERROR_FILE_NOT_FOUND, DHD_ERROR_CONFIGURATION } |
Functions | |
dhdErrorStr __API | dhdErrorGetLastStr () |
dhdErrorStr __API | dhdErrorGetStr (int error) |
int __API | dhdGetDeviceCount () |
int __API | dhdSetDevice (char ID=-1) |
int __API | dhdGetDeviceID () |
int __API | dhdGetSerialNumber (ushort *sn, char ID=-1) |
int __API | dhdOpen () |
int __API | dhdOpenID (char ID) |
int __API | dhdClose (char ID=-1) |
int __API | dhdStop (char ID=-1) |
int __API | dhdGetSystemType (char ID=-1) |
int __API | dhdGetVersion (double *ver, char ID=-1) |
void __API | dhdGetAPIVersion (int *major, int *minor, int *release, int *revision) |
int __API | dhdGetStatus (int status[DHD_MAX_STATUS], char ID=-1) |
int __API | dhdGetDeviceAngleRad (double *angle, char ID=-1) |
int __API | dhdGetDeviceAngleDeg (double *angle, char ID=-1) |
int __API | dhdGetEffectorMass (double *mass, char ID=-1) |
ulong __API | dhdGetSystemCounter () |
int __API | dhdGetButton (int index, char ID=-1) |
bool __API | dhdIsLeftHanded (char ID=-1) |
int __API | dhdReset (char ID=-1) |
int __API | dhdResetWrist (char ID=-1) |
int __API | dhdWaitForReset (int timeout=0, char ID=-1) |
int __API | dhdSetStandardGravity (double g, char ID=-1) |
int __API | dhdSetGravityCompensation (int val=DHD_ON, char ID=-1) |
int __API | dhdSetBrakes (int val=DHD_ON, char ID=-1) |
int __API | dhdSetDeviceAngleRad (double angle, char ID=-1) |
int __API | dhdSetDeviceAngleDeg (double angle, char ID=-1) |
int __API | dhdSetEffectorMass (double mass, char ID=-1) |
int __API | dhdGetPosition (double *px, double *py, double *pz, char ID=-1) |
int __API | dhdGetForce (double *fx, double *fy, double *fz, char ID=-1) |
int __API | dhdSetForce (double fx, double fy, double fz, char ID=-1) |
int __API | dhdGetOrientationRad (double *oa, double *ob, double *og, char ID=-1) |
int __API | dhdGetOrientationDeg (double *oa, double *ob, double *og, char ID=-1) |
int __API | dhdGetTorque (double *ta, double *tb, double *tg, char ID=-1) |
int __API | dhdSetTorque (double ta, double tb, double tg, char ID=-1) |
int __API | dhdGetPositionAndOrientationRad (double *px, double *py, double *pz, double *oa, double *ob, double *og, char ID=-1) |
int __API | dhdGetPositionAndOrientationDeg (double *px, double *py, double *pz, double *oa, double *ob, double *og, char ID=-1) |
int __API | dhdGetPositionAndOrientationFrame (double *px, double *py, double *pz, double matrix[3][3], char ID=-1) |
int __API | dhdGetForceAndTorque (double *fx, double *fy, double *fz, double *ta, double *tb, double *tg, char ID=-1) |
int __API | dhdSetForceAndTorque (double fx, double fy, double fz, double ta, double tb, double tg, char ID=-1) |
int __API | dhdGetOrientationFrame (double matrix[3][3], char ID=-1) |
int __API | dhdGetGripperAngleDeg (double *a, char ID=-1) |
int __API | dhdGetGripperAngleRad (double *a, char ID=-1) |
int __API | dhdGetGripperThumbPos (double *px, double *py, double *pz, char ID=-1) |
int __API | dhdGetGripperFingerPos (double *px, double *py, double *pz, char ID=-1) |
int __API | dhdSetGripperTorque (double t, char ID=-1) |
int __API | dhdSetGripperForce (double f, char ID=-1) |
double __API | dhdGetComFreq (char ID=-1) |
int __API | dhdSetForceAndGripperForce (double fx, double fy, double fz, double f, char ID=-1) |
int __API | dhdSetForceAndGripperTorque (double fx, double fy, double fz, double t, char ID=-1) |
int __API | dhdConfigLinearVelocity (int ms=DHD_VELOCITY_WINDOW, int mode=DHD_VELOCITY_WINDOWING, char ID=-1) |
int __API | dhdGetLinearVelocity (double *vx, double *vy, double *vz, char ID=-1) |
int __API | dhdEmulateButton (uchar val, char ID=-1) |
int __API | dhdEnableExpertMode () |
int __API | dhdDisableExpertMode () |
int __API | dhdPreset (int val[DHD_MAX_ENC], uchar mask, char ID=-1) |
int __API | dhdEnableForce (uchar val, char ID=-1) |
int __API | dhdCalibrateWrist (char ID=-1) |
int __API | dhdSetTimeGuard (int us, char ID=-1) |
int __API | dhdSetVelocityThreshold (uchar val, char ID=-1) |
int __API | dhdGetVelocityThreshold (uchar *val, char ID=-1) |
int __API | dhdUpdateEncoders (char ID=-1) |
int __API | dhdGetDeltaEncoders (int *enc0, int *enc1, int *enc2, char ID=-1) |
int __API | dhdGetWristEncoders (int *enc0, int *enc1, int *enc2, char ID=-1) |
int __API | dhdGetGripperEncoder (int *enc, char ID=-1) |
int __API | dhdGetEncoder (int index, char ID=-1) |
int __API | dhdSetMotor (int index, short val, char ID=-1) |
int __API | dhdSetDeltaMotor (short mot0, short mot1, short mot2, char ID=-1) |
int __API | dhdSetWristMotor (short mot0, short mot1, short mot2, char ID=-1) |
int __API | dhdSetGripperMotor (short mot, char ID=-1) |
int __API | dhdDeltaEncoderToPosition (int enc0, int enc1, int enc2, double *px, double *py, double *pz, char ID=-1) |
int __API | dhdDeltaPositionToEncoder (double px, double py, double pz, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __API | dhdDeltaMotorToForce (short mot0, short mot1, short mot2, int enc0, int enc1, int enc2, double *fx, double *fy, double *fz, char ID=-1) |
int __API | dhdDeltaForceToMotor (double fx, double fy, double fz, int enc0, int enc1, int enc2, short *mot0, short *mot1, short *mot2, char ID=-1) |
int __API | dhdWristEncoderToOrientation (int enc0, int enc1, int enc2, double *oa, double *ob, double *og, char ID=-1) |
int __API | dhdWristOrientationToEncoder (double oa, double ob, double og, int *enc0, int *enc1, int *enc2, char ID=-1) |
int __API | dhdWristMotorToTorque (short mot0, short mot1, short mot2, int enc0, int enc1, int enc2, double *ta, double *tb, double *tg, char ID=-1) |
int __API | dhdWristTorqueToMotor (double ta, double tb, double tg, int enc0, int enc1, int enc2, short *mot0, short *mot1, short *mot2, char ID=-1) |
int __API | dhdGripperEncoderToOrientation (int enc, double *a, char ID=-1) |
int __API | dhdGripperEncoderToPosition (int enc, double *p, char ID=-1) |
int __API | dhdGripperOrientationToEncoder (double a, int *enc, char ID=-1) |
int __API | dhdGripperPositionToEncoder (double p, int *enc, char ID=-1) |
int __API | dhdGripperMotorToTorque (short mot, double *t, char ID=-1) |
int __API | dhdGripperMotorToForce (short mot, double *f, char ID=-1) |
int __API | dhdGripperTorqueToMotor (double t, short *mot, char ID=-1) |
int __API | dhdGripperForceToMotor (double f, short *mot, char ID=-1) |
int __API | dhdSetOperatingMode (unsigned char mode, char ID=-1) |
int __API | dhdGetOperatingMode (unsigned char *mode, char ID=-1) |
int __API | dhdControllerSetDevice (int device, char ID=-1) |
int __API | dhdReadConfigFromFile (char *filename, char ID=-1) |
int __API | dhdSetMot (short mot[DHD_MAX_ENC], uchar mask=0xff, char ID=-1) |
int __API | dhdGetEnc (int enc[DHD_MAX_ENC], uchar mask=0xff, char ID=-1) |
int __API | dhdSetBrk (uchar mask=0xff, char ID=-1) |
bool __API | dhdKbHit () |
char __API | dhdKbGet () |
double __API | dhdGetTime () |
void __API | dhdSleep (double sec) |
const char *__API | dhdGetSystemName (char ID=-1) |
DHD header file.
#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_3DOF 31 |
device ID for the Force Dimension DHD-3DOF haptic device
#define DHD_DEVICE_3DOF_USB 63 |
device ID for the Force Dimension DHD-3DOF haptic device (USB version)
#define DHD_DEVICE_6DOF 61 |
device ID for the Force Dimension DHD-6DOF haptic device
#define DHD_DEVICE_6DOF_500 62 |
device ID for the Force Dimension DHD-6DOF haptic device (high-resolution version)
#define DHD_DEVICE_6DOF_USB 64 |
device ID for the Force Dimension DHD-6DOF haptic device (USB version)
#define DHD_DEVICE_CONTROLLER 81 |
device ID for the Force Dimension stand-alone USB 2.0 controller device
#define DHD_DEVICE_CONTROLLER_HR 82 |
device ID for the Force Dimension stand-alone USB 2.0 controller device with high-resolution encoders (24bits)
#define DHD_DEVICE_CUSTOM 91 |
device ID for an unknown device compatible with the Force Dimension communication protocol
#define DHD_DEVICE_NONE 0 |
device ID returned when no device is connected
#define DHD_DEVICE_OMEGA 32 |
device ID for the Force Dimension OMEGA haptic device
#define DHD_DEVICE_OMEGA3 33 |
device ID for the Force Dimension OMEGA.3 haptic device
#define DHD_DEVICE_OMEGA33 34 |
device ID for the Force Dimension OMEGA.6 haptic device
#define DHD_DEVICE_OMEGA331 35 |
device ID for the Force Dimension OMEGA.7 haptic device
#define DHD_DEVICE_OMEGA331_LEFT 37 |
device ID for the left-handed version of the Force Dimension OMEGA.7 haptic device
#define DHD_DEVICE_OMEGA33_LEFT 36 |
device ID for the left-handed version of the Force Dimension OMEGA.6 haptic device
#define DHD_MAX_BUTTONS 8 |
The maximum number of buttons the API can address on the Force Dimension haptic device.
#define DHD_MAX_DEVICE 4 |
maximum number of devices the API can manage at the same time
maximum number of devices that can be used at the same time
#define DHD_MAX_ENC 8 |
maximum number of encoder channels that are available
#define DHD_MAX_MOTOR 6 |
maximum number of motors that are available
#define DHD_MAX_STATUS 13 |
The length of the status array. See device status for details.
#define DHD_OFF 0 |
applies to the Device Status values
#define DHD_ON 1 |
applies to the Device Status values
#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 DHC.
#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_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_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_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 DHC 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 applied 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 flag in the status array. This flag indicates if the device has a wrist or not. See device types for details.
#define DHD_TIMEGUARD 1 |
return value used when the TimeGuard feature is enabled
#define DHD_VELOCITY_AVERAGING 1 |
The non-default velocity estimator mode. In this mode, the velocity is estimated by averaging all instant velocity measurements taken over a given time interval. This time interval 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 more resource intensive than the DHD_VELOCITY_WINDOWING mode.
#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 less resource intensive than the DHD_VELOCITY_AVERAGING mode.
#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.
DHD_NO_ERROR |
Indicates that no error occurred during processing. This is set as the default value in most of the DHD-3.2 functions. |
DHD_ERROR |
undocumented error (for custom use) |
DHD_ERROR_COM |
communication error between the controller and the host computer |
DHD_ERROR_DHC_BUSY |
the device controller is busy and cannot performed the required task |
DHD_ERROR_NO_DRIVER_FOUND |
a required device driver is not installed, please refer to your user manual installation section |
DHD_ERROR_NO_DEVICE_FOUND |
no compatible Force Dimension device was detected |
DHD_ERROR_NOT_AVAILABLE |
the command or feature is not available for a particular device or software release |
DHD_ERROR_TIMEOUT |
the operation timed out |
DHD_ERROR_GEOMETRY |
an error occurred within the device geometric model (expert mode only) |
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 currently not implemented |
DHD_ERROR_OUT_OF_MEMORY |
memory could not be allocated, please close some applications |
DHD_ERROR_DEVICE_NOT_READY |
the 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/write the calibration data into the device memory |
int __API dhdCalibrateWrist | ( | char | ID | ) |
Trigger the wrist calibration routine in the device controller.
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdClose | ( | char | ID | ) |
Close the connection to a particular device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdConfigLinearVelocity | ( | int | ms, | |
int | mode, | |||
char | ID | |||
) |
Configure the internal velocity computation estimator. This only applies to the translational structure.
ms | [default=20] 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 __API dhdControllerSetDevice | ( | int | device, | |
char | ID | |||
) |
If the connected device is a controller, this function lets you 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 __API dhdDeltaEncoderToPosition | ( | int | enc0, | |
int | enc1, | |||
int | enc2, | |||
double * | px, | |||
double * | py, | |||
double * | pz, | |||
char | ID | |||
) |
Apply the DELTA kinematic model in Cartesian coordinates to a set of known encoder positions. This routine 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 __API dhdDeltaForceToMotor | ( | double | fx, | |
double | fy, | |||
double | fz, | |||
int | enc0, | |||
int | enc1, | |||
int | enc2, | |||
short * | mot0, | |||
short * | mot1, | |||
short * | mot2, | |||
char | ID | |||
) |
Apply the DELTA kinematic model in Cartesian coordinates to a known force applied to the end-effector. This routine 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 __API dhdDeltaMotorToForce | ( | short | mot0, | |
short | mot1, | |||
short | mot2, | |||
int | enc0, | |||
int | enc1, | |||
int | enc2, | |||
double * | fx, | |||
double * | fy, | |||
double * | fz, | |||
char | ID | |||
) |
Apply the DELTA kinematic model in Cartesian coordinates to a set of known motor commands. This routine 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 __API dhdDeltaPositionToEncoder | ( | double | px, | |
double | py, | |||
double | pz, | |||
int * | enc0, | |||
int * | enc1, | |||
int * | enc2, | |||
char | ID | |||
) |
Apply the DELTA kinematic model in Cartesian coordinates to a known end-effector position. This routine 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 __API dhdDisableExpertMode | ( | ) |
Disable the expert mode.
READ USER/PROGRAMMING MANUALS FIRST
USE AT YOUR OWN RISKS
int __API dhdEmulateButton | ( | uchar | val, | |
char | ID | |||
) |
Enable the button behavior emulation in the omega.7 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 __API dhdEnableExpertMode | ( | ) |
Enable the expert mode.
READ USER/PROGRAMMING MANUALS FIRST
USE AT YOUR OWN RISKS
int __API dhdEnableForce | ( | uchar | val, | |
char | ID | |||
) |
Enable 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) |
dhdErrorStr __API dhdErrorGetLastStr | ( | ) |
Returns a brief string describing the last error encountered in the running thread.
dhdErrorStr __API dhdErrorGetStr | ( | int | error | ) |
Returns a brief string describing a given error code.
error | error code |
void __API dhdGetAPIVersion | ( | int * | major, | |
int * | minor, | |||
int * | release, | |||
int * | revision | |||
) |
Return the API complete set of version numbers.
major | major version number | |
minor | minor version number | |
release | release number | |
revision | revision number |
int __API dhdGetButton | ( | int | index, | |
char | ID | |||
) |
Return 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) |
double __API dhdGetComFreq | ( | char | ID | ) |
Return 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 __API dhdGetDeltaEncoders | ( | int * | enc0, | |
int * | enc1, | |||
int * | enc2, | |||
char | ID | |||
) |
Read all the encoders 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 __API dhdGetDeviceAngleDeg | ( | double * | angle, | |
char | ID | |||
) |
Get the device base plate angle.
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 __API dhdGetDeviceAngleRad | ( | double * | angle, | |
char | ID | |||
) |
Get the device base plate angle.
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 __API dhdGetDeviceCount | ( | ) |
Return the number of compatible Force Dimension devices connected to the system. This encompasses all devices, disregarding of their mode of connection (USB or PCI). Devices are enumerated at startup and given a unique identifier, as explained in the multiple devices section. Therefore, it is not possible to add/remove a device to the system while an application with an open connection to any of the devices is running.
int __API dhdGetDeviceID | ( | ) |
Return the ID of the current default device.
int __API dhdGetEffectorMass | ( | double * | mass, | |
char | ID | |||
) |
Get 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 __API dhdGetEnc | ( | int | enc[DHD_MAX_ENC], | |
uchar | mask, | |||
char | ID | |||
) |
Get selective encoder values into encoder array. 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 __API dhdGetEncoder | ( | int | index, | |
char | ID | |||
) |
Read a single encoder from the haptic device.
index | the encoder index number as defined by DHD_MAX_ENC | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetForce | ( | double * | fx, | |
double * | fy, | |||
double * | fz, | |||
char | ID | |||
) |
Retrieve the force that was last 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 __API dhdGetForceAndTorque | ( | double * | fx, | |
double * | fy, | |||
double * | fz, | |||
double * | ta, | |||
double * | tb, | |||
double * | tg, | |||
char | ID | |||
) |
Retrieve the force and torque that was last 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] | |
ta | [out] torque around the X axis in [Nm] | |
tb | [out] torque around the Y axis in [Nm] | |
tg | [out] torque around the Z axis in [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetGripperAngleDeg | ( | double * | a, | |
char | ID | |||
) |
Get the GRIPPER opening in degrees.
a | [out] GRIPPER opening [deg] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetGripperAngleRad | ( | double * | a, | |
char | ID | |||
) |
Get the GRIPPER opening in radians.
a | [out] GRIPPER opening [rad] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetGripperEncoder | ( | int * | enc, | |
char | ID | |||
) |
Read the encoder of the GRIPPER structure.
enc | [out] GRIPPER encoder reading [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetGripperFingerPos | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
char | ID | |||
) |
Get the translation vector to the forefinger rest location of the 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 __API dhdGetGripperThumbPos | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
char | ID | |||
) |
Get the translation vector to the thumb rest location of the 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 __API dhdGetLinearVelocity | ( | double * | vx, | |
double * | vy, | |||
double * | vz, | |||
char | ID | |||
) |
Retrieve the estimated instantaneous translational velocity. Velocity computation must be enabled by calling dhdConfigLinearVelocity(). 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) |
int __API dhdGetOperatingMode | ( | uchar * | mode, | |
char | ID | |||
) |
Get the firmware operating mode on compatible firmware versions.
mode | [out] pointer to the operating mode return value | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetOrientationDeg | ( | double * | oa, | |
double * | ob, | |||
double * | og, | |||
char | ID | |||
) |
Retrieve the orientation of the end-effector in cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.
oa | [out] device orientation around the X axis in [deg] | |
ob | [out] device orientation around the Y axis in [deg] | |
og | [out] device orientation around the Z axis in [deg] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetOrientationFrame | ( | double | matrix[3][3], | |
char | ID | |||
) |
Get the rotation matrix for the rotator if present.
matrix | [out] orientation matrix frame | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetOrientationRad | ( | double * | oa, | |
double * | ob, | |||
double * | og, | |||
char | ID | |||
) |
Retrieve the orientation of the end-effector in cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.
oa | [out] device orientation around the X axis in [rad] | |
ob | [out] device orientation around the Y axis in [rad] | |
og | [out] device orientation around the Z axis in [rad] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetPosition | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
char | ID | |||
) |
Retrieve the position of the end-effector in cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.
px | [out] device position on the X axis in [m] | |
py | [out] device position on the Y axis in [m] | |
pz | [out] device position on the Z axis in [m] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetPositionAndOrientationDeg | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
double * | oa, | |||
double * | ob, | |||
double * | og, | |||
char | ID | |||
) |
Retrieve the position and orientation of the end-effector in cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.
px | [out] device position on the X axis in [m] | |
py | [out] device position on the Y axis in [m] | |
pz | [out] device position on the Z axis in [m] | |
oa | [out] device orientation around the X axis in [deg] | |
ob | [out] device orientation around the Y axis in [deg] | |
og | [out] device orientation around the Z axis in [deg] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetPositionAndOrientationFrame | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
double | matrix[3][3], | |||
char | ID | |||
) |
Retrieve the position and orientation 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 __API dhdGetPositionAndOrientationRad | ( | double * | px, | |
double * | py, | |||
double * | pz, | |||
double * | oa, | |||
double * | ob, | |||
double * | og, | |||
char | ID | |||
) |
Retrieve the position and orientation of the end-effector in cartesian coordinates. Please refer to your device user manual for more information on your device coordinate system.
px | [out] device position on the X axis in [m] | |
py | [out] device position on the Y axis in [m] | |
pz | [out] device position on the Z axis in [m] | |
oa | [out] device orientation around the X axis in [rad] | |
ob | [out] device orientation around the Y axis in [rad] | |
og | [out] device orientation around the Z axis in [rad] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetSerialNumber | ( | ushort * | sn, | |
char | ID | |||
) |
Return 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 __API dhdGetStatus | ( | int | status[DHD_MAX_STATUS], | |
char | ID | |||
) |
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 __API dhdGetSystemCounter | ( | ) |
Returns the current value from the high-resolution system counter in [ms]. The resolution of the system counter may be machine-dependent, as it usually derived from one of the CPU clocks signals.
const char* __API dhdGetSystemName | ( | char | ID | ) |
Return the haptic device type. As this API 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 __API dhdGetSystemType | ( | char | ID | ) |
Return the haptic device type. As this API 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 __API dhdGetTime | ( | ) |
Returns the current value from the high-resolution system counter in [s]. The resolution of the system counter may be machine-dependent, as it usually derived from one of the CPU clocks signals. The time returned is guaranteed to be monotonic.
int __API dhdGetTorque | ( | double * | ta, | |
double * | tb, | |||
double * | tg, | |||
char | ID | |||
) |
Retrieve the torque that was last applied to the device end-effector.
ta | [out] torque around the X axis in [Nm] | |
tb | [out] torque around the Y axis in [Nm] | |
tg | [out] torque around the Z axis in [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGetVelocityThreshold | ( | uchar * | val, | |
char | ID | |||
) |
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 __API dhdGetVersion | ( | double * | ver, | |
char | ID | |||
) |
Return the device controller version. As this API 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 __API dhdGetWristEncoders | ( | int * | enc0, | |
int * | enc1, | |||
int * | enc2, | |||
char | ID | |||
) |
Read all the encoders of the WRIST structure.
enc0 | [out] WRIST axis 0 encoder reading [] | |
enc1 | [out] WRIST axis 1 encoder reading [] | |
enc2 | [out] WRIST axis 2 encoder reading [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperEncoderToOrientation | ( | int | enc, | |
double * | a, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known encoder position. This routine computes and returns the opening of the gripper 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 __API dhdGripperEncoderToPosition | ( | int | enc, | |
double * | p, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known encoder position. This routine computes and returns the opening of the gripper for a given encoder reading.
enc | GRIPPER encoder reading [] | |
p | [out] GRIPPER opening [m] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperForceToMotor | ( | double | f, | |
short * | mot, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known force applied to the end-effector. This routine computes and returns the motor commands necessary to obtain a given force on the grasping structure.
f | force on the GRIPPER end-effector [N] | |
mot | [out] motor command on GRIPPER axis [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperMotorToForce | ( | short | mot, | |
double * | f, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known motor commands. This routine computes and returns the force applied to the end-effector for a given motor command.
mot | motor command on GRIPPER axis [] | |
f | [out] force on the GRIPPER end-effector [N] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperMotorToTorque | ( | short | mot, | |
double * | t, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known motor commands. This routine computes and returns the torque applied to the end-effector for a given motor command.
mot | motor command on GRIPPER axis [] | |
t | [out] torque on the GRIPPER end-effector [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperOrientationToEncoder | ( | double | a, | |
int * | enc, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known gripper opening. This routine computes and returns the encoder values for a given gripper angle.
a | GRIPPER end-effector opening [rad] | |
enc | [out] GRIPPER encoder reading [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperPositionToEncoder | ( | double | p, | |
int * | enc, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known gripper opening. This routine computes and returns the encoder values for a given gripper opening.
p | GRIPPER end-effector position [m] | |
enc | [out] GRIPPER encoder reading [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdGripperTorqueToMotor | ( | double | t, | |
short * | mot, | |||
char | ID | |||
) |
Apply the GRIPPER kinematic model in Cartesian coordinates to a known torque applied to the end-effector. This routine computes and returns the motor commands necessary to obtain a given torque on the grasping structure.
t | torque on the GRIPPER end-effector [Nm] | |
mot | [out] motor command on GRIPPER axis [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
bool __API dhdIsLeftHanded | ( | char | ID | ) |
Returns true if the device is configured for left-handed use.
ID | [default=-1] device ID (see multiple devices section for details) |
char __API dhdKbGet | ( | ) |
Retrieve a character from the keyboard (OS independent).
bool __API dhdKbHit | ( | ) |
Check keyboard for a key hit (OS independent).
int __API dhdOpen | ( | ) |
Open a connection to the first device connected to the system. If more than one device are connected, USB devices will always be opened before PCI devices. To open connections to multiple devices, use the dhdOpenID() call.
int __API dhdOpenID | ( | char | ID | ) |
Open a connection to one particular device connected to the system. PCI-connected devices are opened first, followed by USB-connected devices. The order in which devices are opened is predictable and remains the same until system configuration changes.
ID | the device ID (must be between 0 and the number of devices connected to the system) |
int __API dhdPreset | ( | int | val[DHD_MAX_ENC], | |
uchar | mask, | |||
char | ID | |||
) |
Set 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 | [default=0xff] bitwise mask of which encoder should be set | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdReadConfigFromFile | ( | char * | filename, | |
char | ID | |||
) |
Load 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 __API dhdReset | ( | char | ID | ) |
Puts the device in RESET mode.
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdResetWrist | ( | char | ID | ) |
Puts the device rotator extension in RESET mode.
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetBrakes | ( | int | val, | |
char | ID | |||
) |
Enable/disable the device electromagnetic brakes.
val | desired state of the brakes (DHD_ON or DHD_OFF) | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetBrk | ( | uchar | mask, | |
char | ID | |||
) |
Set 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 brakes will be activated.int __API dhdSetDeltaMotor | ( | short | mot0, | |
short | mot1, | |||
short | mot2, | |||
char | ID | |||
) |
Set all the motors of the DELTA structure.
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 __API dhdSetDevice | ( | char | ID | ) |
Select the default device that will receive the API commands. The API supports multiple devices. This routine allows the programmer to decide which device the API single_device_call single-device calls will address. Any subsequent API call that does not specifically mention the device ID in its parameter list will be sent to that device.
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetDeviceAngleDeg | ( | double | angle, | |
char | ID | |||
) |
Set the device base plate angle.
angle | device base plate angle [deg] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetDeviceAngleRad | ( | double | angle, | |
char | ID | |||
) |
Set the device base plate angle.
angle | device base plate angle [rad] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetEffectorMass | ( | double | mass, | |
char | ID | |||
) |
Define 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 __API dhdSetForce | ( | double | fx, | |
double | fy, | |||
double | fz, | |||
char | ID | |||
) |
Set the force 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 __API dhdSetForceAndGripperForce | ( | double | fx, | |
double | fy, | |||
double | fz, | |||
double | f, | |||
char | ID | |||
) |
Set delta force and gripper force.
fx | translation force along X axis | |
fy | translation force along Y axis | |
fz | translation force along Z axis | |
f | grasping force | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetForceAndGripperTorque | ( | double | fx, | |
double | fy, | |||
double | fz, | |||
double | t, | |||
char | ID | |||
) |
Set delta and gripper force.
fx | translation force along X axis | |
fy | translation force along Y axis | |
fz | translation force along Z axis | |
t | grasping torque | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetForceAndTorque | ( | double | fx, | |
double | fy, | |||
double | fz, | |||
double | ta, | |||
double | tb, | |||
double | tg, | |||
char | ID | |||
) |
Set the force and torque 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] | |
ta | torque around the X axis in [Nm] | |
tb | torque around the Y axis in [Nm] | |
tg | torque around the Z axis in [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetGravityCompensation | ( | int | val, | |
char | ID | |||
) |
Enable/disable gravity compensation.
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 __API dhdSetGripperForce | ( | double | f, | |
char | ID | |||
) |
Set gripper force.
f | force to apply in N | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetGripperMotor | ( | short | mot, | |
char | ID | |||
) |
Set the motor of the GRIPPER structure.
mot | GRIPPER motor command [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetGripperTorque | ( | double | t, | |
char | ID | |||
) |
Set gripper torque.
t | torque to apply in Nm | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetMot | ( | short | mot[DHD_MAX_ENC], | |
uchar | mask, | |||
char | ID | |||
) |
Set selected motor values in the device controller. Particularly useful when using the 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 __API dhdSetMotor | ( | int | index, | |
short | val, | |||
char | ID | |||
) |
Set the DAC value on a single one of the haptic device motors.
index | the motor index number as defined by DHD_MAX_MOTOR | |
val | the motor DAC value [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetOperatingMode | ( | uchar | mode, | |
char | ID | |||
) |
Set the firmware operating mode on compatible firmware versions.
mode | desired operating mode | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetStandardGravity | ( | double | g, | |
char | ID | |||
) |
Set 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 __API dhdSetTimeGuard | ( | int | us, | |
char | ID | |||
) |
Enable/disable 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 __API dhdSetTorque | ( | double | ta, | |
double | tb, | |||
double | tg, | |||
char | ID | |||
) |
Set the torque to be applied to the end-effector of the device.
ta | torque around the X axis in [Nm] | |
tb | torque around the Y axis in [Nm] | |
tg | torque around the Z axis in [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdSetVelocityThreshold | ( | uchar | val, | |
char | ID | |||
) |
Adjust 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 __API dhdSetWristMotor | ( | short | mot0, | |
short | mot1, | |||
short | mot2, | |||
char | ID | |||
) |
Set all the motors of the WRIST structure.
mot0 | WRIST axis 0 motor command [] | |
mot1 | WRIST axis 1 motor command [] | |
mot2 | WRIST axis 2 motor command [] | |
ID | [default=-1] device ID (see multiple devices section for details) |
void __API dhdSleep | ( | double | sec | ) |
Sleep for a given period of time (OS independent).
sec | sleep period in [s] |
int __API dhdStop | ( | char | ID | ) |
Stop 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 __API dhdUpdateEncoders | ( | char | ID | ) |
Force 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 __API dhdWaitForReset | ( | int | timeout, | |
char | ID | |||
) |
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 __API dhdWristEncoderToOrientation | ( | int | enc0, | |
int | enc1, | |||
int | enc2, | |||
double * | oa, | |||
double * | ob, | |||
double * | og, | |||
char | ID | |||
) |
Apply the WRIST kinematic model in Cartesian coordinates to a set of known encoder positions. This routine computes and returns the orientation of the end-effector 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 [] | |
oa | [out] WRIST end-effector orientation around the X axis [rad] | |
ob | [out] WRIST end-effector orientation around the Y axis [rad] | |
og | [out] WRIST end-effector orientation around the Z axis [rad] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdWristMotorToTorque | ( | short | mot0, | |
short | mot1, | |||
short | mot2, | |||
int | enc0, | |||
int | enc1, | |||
int | enc2, | |||
double * | ta, | |||
double * | tb, | |||
double * | tg, | |||
char | ID | |||
) |
Apply the WRIST kinematic model in Cartesian coordinates to a set of known motor commands. This routine 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 axis 0 [] | |
mot1 | motor command around WRIST axis 1 [] | |
mot2 | motor command around WRIST axis 2 [] | |
enc0 | WRIST encoder reading around axis 0 [] | |
enc1 | WRIST encoder reading around axis 1 [] | |
enc2 | WRIST encoder reading around axis 2 [] | |
ta | [out] torque on the WRIST end-effector around the X axis [Nm] | |
tb | [out] torque on the WRIST end-effector around the Y axis [Nm] | |
tg | [out] torque on the WRIST end-effector around the Z axis [Nm] | |
ID | [default=-1] device ID (see multiple devices section for details) |
int __API dhdWristOrientationToEncoder | ( | double | oa, | |
double | ob, | |||
double | og, | |||
int * | enc0, | |||
int * | enc1, | |||
int * | enc2, | |||
char | ID | |||
) |
Apply the WRIST kinematic model in Cartesian coordinates to a known end-effector orientation. This routine computes and returns the encoder values for a given end-effector orientation.
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 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 __API dhdWristTorqueToMotor | ( | double | ta, | |
double | tb, | |||
double | tg, | |||
int | enc0, | |||
int | enc1, | |||
int | enc2, | |||
short * | mot0, | |||
short * | mot1, | |||
short * | mot2, | |||
char | ID | |||
) |
Apply the WRIST kinematic model in Cartesian coordinates to a known torque applied to the end-effector. This routine computes and returns the motor command necessary to obtain a given torque on the end-effector at a given orientation (defined by encoder readings).
ta | torque on the WRIST end-effector around the X axis [Nm] | |
tb | torque on the WRIST end-effector around the Y axis [Nm] | |
tg | 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 axis 0 [] | |
mot1 | [out] motor command around WRIST axis 1 [] | |
mot2 | [out] motor command around WRIST axis 2 [] | |
ID | [default=-1] device ID (see multiple devices section for details) |