DHD - Haptic SDK Documentation

Introduction

This document provides an on-line description of the DHD calls and the related functionalities of the Force Dimension haptic devices. It presents a detailed syntax of each function and its arguments, and explains the programming concepts and features that will help the programmer get the best performance out of Force Dimension haptic devices.

Multi-platforms

The DHD is transparently multi-platform. Currently, implementations exist on

  • Microsoft Windows
  • Linux
  • Apple macOS

The DHD is also available for the following Real-Time Operating Systems (RTOS):

  • Blackberry QNX
  • Wind River VxWorks
  • Microsoft Windows CE7

The only requirement imposed by the multi-platform architecture of the DHD is the use of a preprocessor directive that matches your target system, as indicated in dhdc.h :

  • WIN32 must be defined for Microsoft Windows 32-bit compilation
  • WIN64 must be defined for Microsoft Windows 64-bit platforms
  • LINUX must be defined for Linux platforms
  • MACOSX must be defined for Apple MacOS X platforms
  • QNX must be defined for QNX platforms
  • VXWORKS must be defined for VxWorks platforms

High-level vs. Low-level SDK

The DHD is designed with two purposes in mind:

  • to offer a simple and straightforward software library for programmers to interface their haptic device with their application with just a few lines of code
  • to offer advanced control functionalities for experienced users who wish to write advanced control routines and adjust low-level parameters

The following sections describe the basic device features from a software perspective.

Features

Device Types

This version of the DHD can be used with the following devices:

Unknown devices that comply with the same protocol are referenced by DHD_DEVICE_CUSTOM.

Axis Convention

Unless otherwise specified (e.g. for a specific device), the following convention is used when passing Cartesian data to a function in an array of the form:

double array[DHD_MAX_DOF]
  • For positions and rotations:
    • Position data is stored in
      array[0], array[1], array[2]
    • Euler angles are stored in
      array[3], array[4], array[5]
    • Gripper opening is stored as the gripper opening distance in
      array[6]
  • For velocities:
    • Linear (Cartesian) velocity is stored in
      array[0], array[1], array[2]
    • Angular (Cartesian) velocity are stored in
      array[3], array[4], array[5]
    • Gripper opening distance velocity is stored in
      array[6]
  • For forces and torques:
    • Cartesian force is stored as a vector
      array[0], array[1], array[2]
    • Cartesian torque is stored as a vector
      array[3], array[4], array[5]
    • Gripper force is stored in
      array[6]

Device Modes

When a device is active (powered ON), it is in one of the four states or 'modes' described below. For additional information, please refer to the user manuals.

  • RESET mode
    In this mode, the user is expected to put the device end-effector at its rest position. This is how the device performs its calibration. A calibration can be explicitly required by calling dhdReset().
  • IDLE mode
    In this mode, the position of the end-effector can be read, but no current is applied to the device motors. This is a safe way to debug an application, or to use the device as a pointer. The device can be forced into IDLE mode by disabling the brakes via dhdSetBrakes().
  • FORCE mode
    In this mode, the device motors are enabled so that forces and optionally torques (for 6DOF devices) can be applied.
  • BRAKE mode
    In this mode, electromagnetic braking is applied on the motors. As a result, there is added viscosity that prevents the end-effector from moving rapidly. This mode is entered when forces are disabled, or if a safety features triggers it.

Device Status

Force Dimension haptic devices status can be retrieved via the dhdGetStatus() function. The function returns a status vector containing the following fields:

Support for Multiple Devices

The DHD supports as many haptic devices connected to the same computer as the underlying operating system can accommodate. Once a device is opened, it receives an ID that uniquely identifies it within the SDK. The device that receives the commands from the SDK can be identified and selected at any time by calling dhdGetDeviceID() and dhdSetDevice(). Also, every device specific function of the SDK can take as a last argument the device ID. If no last argument is given, or if that last argument is -1 (the default), the default device is used.

Velocity Estimator

The SDK provides internal mechanisms that estimate the velocity of the device in the joint and cartesian coordinate systems. The default velocity estimator configuration should be suitable for most use cases, but can be reconfigured by calling:

The estimated velocity can be retrieved by calling:

Note that in this release, velocity is computed using DHD_VELOCITY_WINDOWING mode.

TimeGuard

The DHD features a throttling mechanism to provide a controllable communication refresh rate while preserving resources on non real-time OS. This mechanism prevents the OS from querying the device for its position at a rate higher than an adjustable threshold. In order to do so, TimeGuard prevents the application from requesting new position data if recent data from an earlier communication event is still recent enough. This mechanism can remove communication overhead without affecting performance if set properly, but can also significantly affect performance if set to the wrong value. It is recommended to leave the TimeGuard feature to its default setting unless a specific software architecture requires it. SDK calls that trigger the TimeGuard feature will return DHD_TIMEGUARD if communication with the device was not necessary, 0 otherwise (or see error management for possible return values). See dhdSetTimeGuard() to adjust this feature.

Thread-Safe Operation

Every module of the SDK is thread-safe. Programmers need not add their own synchronizing mechanism to control access to the device or its geometric model.

Multi-threading

Multi-threading operation is fully supported by the SDK (see Thread-Safe Operation above). The SDK provides a simple convenience function (dhdStartThread()) to start threads with a portable, operating system independent syntax. For more complex thread management, Force Dimension recommends using the native thread libraries of each operating system.

The dhdStartThread() function allows to start any C-like function in a separate thread, with an optional argument and a given priority level. The priority level is defined in a portable, operating system independent way as:

Error Management

The DHD uses a thread-safe global accessible via dhdErrorGetLast(), to store the last error that occurred in each running thread. Most functions and methods will return either 0 or a valid, positive value on success, and -1 (or NULL) in case of failure. On failure, programmers can check the value of dhdErrorGetLast() against the error values.

To help identify the error, the dhdErrorGetStr() functions return a short descriptive string. Similarly, dhdErrorGetLastStr() returns a string describing the last error that occurred within the calling thread.

The following functions can be used to retrieve error codes and their descriptions:

Safety Feature

As Force Dimension haptic devices can generate a significant amount of force, it could accelerate to a point that may damage the system, or surprise unaware users. To prevent such situations, the controller factory settings offer a safety feature that forces the device into BRAKE mode if the velocity becomes greater than a given threshold. While it is possible to modify this value using advanced features from this SDK, it is recommended to keep this threshold as low as the application requires.

Units

Here is an overview of the units used in the SDK, unless otherwise specified:

  • length : meter [m]
  • angles : radian [rad] or [deg] (specified)
  • forces : newton [N]
  • torques : newton.meter [Nm]
  • time : microsecond [us]

Standard SDK

The following functions can be called at any time.

Expert SDK

This SDK offers high-level functions and methods that make it very easy to interface a Force Dimension haptic Device with any application. However, in some cases, users might want to get direct access to lower-level functionalities of the device (such as encoder readings and direct motor command) The SDK allows advanced users to access these routines by enabling the expert mode. Please note that the expert mode is for experienced programmers who have a thorough understanding of their haptic interface. Force Dimension cannot be held responsible for any damage resulting from use of the expert mode. The following functions are part of the expert SDK and require a deep understanding of control theory, as well as of the device design itself.
USE AT YOUR OWN RISK !

Controller SDK

The following functions only apply to the DHD_DEVICE_CONTROLLER and DHD_DEVICE_CONTROLLER_HR devices.

OS-independent SDK

Technical Support

Please contact your distributor for any technical support inquiry.

DHD_MAX_DOF
#define DHD_MAX_DOF
Definition: dhdc.h:133