forcedimension_core.dhd.expert module

forcedimension_core.dhd.expert.controllerSetDevice(devtype: DeviceType, ID: int = -1) int[source]

If the connected device is a controller 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.

Parameters:
Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaEncoderToPosition(enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

Compute and return the position of the end-effector (in [m]) about the X, Y, and Z axes for a given set of encoder values.

Parameters:
  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to raw encoder values on axis 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the end-effector position (in [m]).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaEncodersToJointAngles(enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

Compute and return the DELTA joint angles for a given set of encoder values.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaForceToMotor(f: Array[int, float], enc: Array[int, int], out: MutableArray[int, int], ID: int = -1) int[source]

Compute and return the motor commands necessary to obtain a given force on the end-effector at a given position (defined by encoder readings).

Parameters:
  • f (Array[int, float]) – Sequence of (fx, fy, fz) where fx, fy, and fz are the force on the DELTA end-effector on the X, Y, and Z axes, respectively (in [N]).

  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to encoder values on axes 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the applied force to the end-effector.

Raises:
Returns:

0 or forcedimension_core.constants.MOTOR_SATURATED on success, and -1 otherwise.

forcedimension_core.dhd.expert.deltaGravityJointTorques(joint_angles: Array[int, float], out: MutableArray[int, float], ID: int = -1) int[source]

Compute 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.

Deprecated since version 1.0.0: Force Dimension SDK v3.16.0+ recommends that you use forcedimension_core.dhd.expert.jointAnglesToGravityJointTorques() instead.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaJointAnglesToEncoders(joint_angles: Array[int, float], out: MutableArray[int, int], ID: int = -1) int[source]

Compute and return the DELTA encoder values for a given set of joint angles.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaJointAnglesToJacobian(joint_angles: Array[int, float], out: Array[int, MutableArray[int, float]], ID: int = -1) int[source]

Retrieve the 3x3 jacobian matrix for the DELTA structure based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.

Parameters:
  • joint_angles (Array[int, float]) – Sequence of (j0, j1, j2) where j0, j1, and j2 refer to the joint angles for axes 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (MutableFloatMatrixLike) – An output buffer to store the return.

Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaJointTorquesExtrema(joint_angles: Array[int, float], minq_out: MutableArray[int, float], maxq_out: MutableArray[int, float], ID: int = -1) int[source]

Compute 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.

Parameters:
Raises:
  • TypeError – If minq_out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(encMin_out) < MAX_DOF

  • TypeError – If maxq_out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < MAX_DOF

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaMotorToForce(mot: Array[int, int], enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

Compute and return the force applied to the end-effector for a given set of motor commands at a given position (defined by encoder readings)

Parameters:
  • mot (Array[int, int]) – Sequence of (mot0, mot1, mot2) where mot0, mot1, and mot2 are the axis 0, 1, and 2 DELTA motor commands, respectively.

  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to encoder values on axis 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (MutableArray[int, float]) – An output buffer to store the applied force to the end effector.

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.deltaPositionToEncoder(pos: Array[int, float], out: MutableArray[int, int], ID: int = -1) int[source]

Computes and returns the encoder values of the end-effector for a given end-effector position.

Parameters:
  • pos (Array[int, float]) – Sequence of (px, py, pz) where px, py, and pz refer to the end-effector position on the X, Y, and Z axes, respectively (in [m]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the raw encoder values.

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.disableExpertMode() int[source]

Disable expert mode.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.enableExpertMode() int[source]

Enable expert mode.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.getDeltaEncoders(out: MutableArray[int, int], ID: int = -1) int[source]

Read all encoders values of the DELTA structure.

Parameters:
Raises:
Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, and -1 otherwise.

forcedimension_core.dhd.expert.getDeltaJacobian(out: Array[int, MutableArray[int, float]], ID: int = -1) int[source]

Retrieve the 3x3 jacobian matrix for the DELTA structure based on the current end-effector position. Please refer to your device user manual for more information on your device coordinate system.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If any dimension of out is less than 3.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getDeltaJointAngles(out: MutableArray[int, float], ID: int = -1) int[source]

Retrieve the joint angles (in [rad]) for the DELTA structure.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getEnc(out: MutableArray[int, int], mask: int = 255, ID: int = -1) int[source]

Get a selective list of encoder values. Particularly useful when using the generic controller directly, without a device model attached.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < MAX_DOF

  • ctypes.ArgumentError – If mask is not implicitly convertible to a C char.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getEncRange(enc_min_out: MutableArray[int, int], enc_max_out: MutableArray[int, int], ID: int = -1) int[source]

Get the expected min and max encoder values for all axes present on the current device. Axis indices that do not exist on the device will return a range of 0.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.getEncVelocities(out: MutableArray[int, float], ID: int = -1) int[source]

Retrieve the encoder angle velocities (in [inc/s]) for all sensed degrees-of-freedom of the current device.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < MAX_DOF

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getEncoder(index: int, ID: int = -1) int[source]

Read a single encoder value from the haptic device.

Parameters:
Raises:
Returns:

The (positive) encoder reading on success, -1 otherwise.

forcedimension_core.dhd.expert.getGripperEncoder(out: c_int, ID: int = -1) int[source]

Read the encoder value of the force gripper.

Note

This feature only applies to devices with a gripper. See the Device Types section for more details.

Parameters:
  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (c_int) – Output buffer to store the encoder value of the force gripper.

Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getJointAngleRange(jmin_out: MutableArray[int, float], jmax_out: MutableArray[int, float], ID: int = -1) Tuple[Tuple[float, float, float, float, float, float, float, float], Tuple[float, float, float, float, float, float, float, float], int][source]

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.

Parameters:
Raises:
Returns:

0 on success and -1 otherwise.

forcedimension_core.dhd.expert.getJointAngles(out: MutableArray[int, float], ID: int = -1) int[source]

Retrieve the joint angles (in [rad]) for all sensed degrees-of-freedom of the current device.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < MAX_DOF

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getJointVelocities(out: MutableArray[int, float], ID: int = -1) int[source]

Retrieve the joint angle velocities (in [rad/s]) for all sensed degrees-of-freedom of the current device.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < MAX_DOF

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.getVelocityThreshold(ID: int = -1) int[source]

Get the velocity threshold of the device. The 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 BRAKE mode.

Parameters:

ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

The non-negative velocity threshold on success, -1 otherwise.

forcedimension_core.dhd.expert.getWatchdog(ID: int = -1) int[source]

Get the watchdog duration in multiples of 125 us on compatible devices.

Parameters:

ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

The (non-negative) watchdog duration on success, -1 otherwise.

forcedimension_core.dhd.expert.getWristEncoders(out: MutableArray[int, int], ID: int = -1) int[source]

Read all encoders values of the WRIST structure.

Note

This feature only applies to devices with a wrist. See the Device Types section for more details.

Parameters:
Raises:
Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

See also

forcedimension_core.dhd.wristEncodersToOrientation()
forcedimension_core.dhd.wristEncodersToJointAngles()
forcedimension_core.dhd.wristOrientationToEncoder()
forcedimension_core.dhd.expert.getWristJacobian(out: Array[int, MutableArray[int, float]], ID: int = -1) int[source]

Retrieve the 3x3 jacobian matrix for the wrist structure based on the current end-effector position. Please refer to your device user manual for more information on your device coordinate system.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If any dimension of out is less than 3.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, and -1 otherwise.

forcedimension_core.dhd.expert.getWristJointAngles(out: MutableArray[int, float], ID: int = -1) int[source]

Retrieve the joint angles (in [rad]) for the wrist structure.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

See also

forcedimension_core.dhd.expert.dhdWristJointAnglesToJacobian()
forcedimension_core.dhd.expert.dhdWristJointTorquesExtrema()
forcedimension_core.dhd.expert.gripperAngleRadToEncoder(angle: float, out: c_int, ID: int = -1) int[source]

Computes and return the gripper encoder value for a given gripper opening distance (in [rad]).

Note

This feature only applies to devices with a gripper. See the Device Types section for more details.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.gripperEncoderToAngleRad(enc: int, out: c_double, ID: int = -1) int[source]

Compute the gripper angle (in [rad]) for a given encoder value.

Note

This feature only applies to devices with a gripper. See the Device Types section for more details.

Parameters:
  • enc (int) – Gripper encoder reading.

  • out (c_int) – Output buffer to store the gripper angle (in [rad]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 or forcedimension_core.constants.TIMEGUARD on success, -1 otherwise.

forcedimension_core.dhd.expert.gripperEncoderToGap(enc: int, out: c_double, ID: int = -1) int[source]

Compute and return the gripper opening (in [m]) for a given encoder reading.

Note

This feature only applies to devices with a gripper. See the Device Types section for more details.

Parameters:
  • enc (int) – Gripper encoder reading.

  • out (c_double) – Buffer to store the griper opening (in [m]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.gripperForceToMotor(f: float, enc_wrist: Array[int, int], enc_gripper: int, out: c_ushort, ID: int = -1) int[source]

Given a desired force (in [N]) to be displayed by the force gripper, compute and return the refering motor command.

Note

This feature only applies to devices with an active gripper. See the Device Types section for more details.

Parameters:
  • f (int) – Force on the gripper end-effector (in [N]).

  • enc_wrist (Array[int, int]) – An output buffer to store the wrist encoding readings.

  • out (c_ushort) – Output buffer to store the motor command.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 or forcedimension_core.constants.MOTOR_SATURATED on success, -1 otherwise.

forcedimension_core.dhd.expert.gripperGapToEncoder(gap: float, out: c_int, ID: int = -1) int[source]

Compute and return the gripper encoder value for a given gripper opening distance (in [m]).

Note

This feature only applies to devices with a gripper. See the Device Types section for more details.

param float gap:

Gripper opening distance (in [m]).

param c_int out:

Outpu buffer to store the gripper encoder value.

param int ID:

Device ID (see Support for Multiple Devices section for details).

raises ctypes.ArgumentError:

If gap is not implicitly convertible to a C char.

raises ctypes.ArgumentError:

If ID is not implicitly convertible to a C char.

returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.gripperMotorToForce(cmd: int, enc_wrist: Array[int, int], enc_gripper: int, out: c_double, ID: int = -1) int[source]

Compute the force applied to the end-effector for a given motor command.

Note

This feature only applies to devices with an active gripper. See the Device Types section for more details.

Parameters:
  • output (int) – Motor command on gripper axis.

  • enc_wrist (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, enc2 are encoder values about wrist joints 0, 1, and 2, respectively.

  • enc_gripper (int) – Encoder reading for the gripper.

  • out (c_double) – Output buffer to store the force applied to the end effector (in [N]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.jointAnglesToGravityJointTorques(joint_angles: Array[int, float], out: MutableArray[int, float], mask: int = 255, ID: int = -1) int[source]

This function computes the joint torques (in [Nm]) required to provide gravity compensation on all actuated degrees-of-freedom of the current device for a given joint angles configuration (in [rad]).

Parameters:
  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • mask (int) – Bitwise mask of which joint torques should be computed.

  • out (MutableFloatMatrixLike) – Output buffer for the joint torques required to provide gravity compensation (in [Nm]).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.jointAnglesToIntertiaMatrix(joint_angles: Array[int, float], out: Array[int, MutableArray[int, float]], ID: int = -1) int[source]

Retrieve the inertia matrix based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.

Parameters:
Raises:
  • ctypes.ArgumentError – If joint_angles is not implicitly convertible to a C char.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If of the any dimension of out is less than 6.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.preloadMot(cmds: Array[int, int], mask: int = 255, ID: int = -1) int[source]

Program motor commands to a selection of motor channels. Unlike forcedimension_core.dhd.expert.setMot(), this function saves the requested commands internally for later application by calling forcedimension_core.dhd.setForce() and the friends.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.preset(val: Array[int, int], mask: int = 255, ID: int = -1) int[source]

Set selected encoder offsets to a given value. Intended for use with the generic controller when no RESET button is available.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.readConfigFromFile(filename: str, ID: int = -1)[source]

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 forcedimension_core.dhd.controllerSetDevice() call.

Parameters:
Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setBrk(mask: int = 255, ID: int = -1) int[source]

Set electromagnetic braking status on selective motor groups. Only applies when using the generic controller directly, without a device model attached.

Generic control motor groups

group1 - [mot0, mot1, mot2]

group2 - [mot3, mot4, mot5]

group3 - [mot6]

group4 - [mot7]

The mask parameter addresses all 8 motors bitwise. If a single bit within a motor group’s is enabled, all motors in that motor’s group’s electromagnetic brakes will be activated.

Parameters:
  • mask – Bitwise mask of which motor groups should have their electromagnetic brakes be set on.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.setComMode(mode: ComMode, ID: int = -1) int[source]

Set the COM operation mode on compatible devices.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

See also

forcedimension_core.dhd.expert.setComModePriority()
forcedimension_core.dhd.expert.setDeltaJointTorques(q: Array[int, float], ID: int = -1) int[source]

Set all joint torques of the DELTA structure.

Parameters:

t (Array[int, float]) – Sequence of (t0, t1, t2) where t0, t1, and t2 are the DELTA axis torque commands for axes 0, 1, and 2, respectively (in [Nm]).

Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.setDeltaMotor(mot: Array[int, int], ID: int = -1) int[source]

Set desired motor commands to the amplifier channels commanding the DELTA motors.

Parameters:
  • mot (Array[int, int]) – Sequence of (mot0, mot1, mot2) where mot0, mot1, and mot2 are the axis 0, 1, and 2 DELTA motor commands, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setForceAndWristJointTorques(f: Array[int, float], t: Array[int, float], ID: int = -1) int[source]

Set force (in [N]) and wrist joint torques (in [Nm]) about the X, Y, and Z axes.

Parameters:
  • f (Array[int, float]) – Sequence of (fx, fy, fz) where fx, fy, and fz are the translation forces (in [N]) to be applied to the DELTA end-effector on the X, Y, and Z axes respectively.

  • t (Array[int, float]) – Sequence of (t0, t1, t2) where t0, t1, t2 are the wrist joint torques (in [Nm]) to be applied to the wrist end-effector for axes 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.setForceAndWristJointTorquesAndGripperForce(f: Array[int, float], t: Array[int, float], fg: float, ID: int = -1) int[source]

Set force (in [N]) and wrist joint torques (in [Nm]) about the X, Y, and Z axes as well as the and gripper force.

Parameters:
  • f (Array[int, float]) – Sequence of (fx, fy, fz) where fx, fy, and fz are the translation forces (in [N]) to be applied to the DELTA end-effector on the X, Y, and Z axes respectively.

  • t (Array[int, float]) – Sequence of (t0, t1, t2) where t0, t1, t2 are the wrist joint torques (in [Nm]) to be applied to the wrist end-effector for axes 0, 1, and 2, respectively.

  • fg (float) – Gripper force (in [N]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.setGripperMotor(output: int, ID: int = -1) int[source]

Set desired motor commands to the amplifier channels commanding the force gripper.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

See also

forcedimension_core.dhd.setMot()
forcedimension_core.dhd.setMotor()
forcedimension_core.dhd.setDeltaMotor()
forcedimension_core.dhd.setWristMotor()
forcedimension_core.dhd.expert.setJointTorques(q: Array[int, float], mask: int = 255, ID: int = -1)[source]

Sets all joint torques on all active axes.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setMot(cmds: Array[int, int], mask: int = 255, ID: int = -1) int[source]

Program motor commands to a selection of motor channels. Particularly useful when using the generic controller directly, without a device model attached.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.setMotor(index: int, output: int, ID: int = -1) int[source]

Program a command to a single motor channel.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setTimeGuard(min_period: int, ID: int = -1) int[source]

Enable/disable the :ref:timeguard: feature with an arbitrary minimum period.

Parameters:
  • min_period (int) – Minimum refresh period (in [us]). A value of 0. disables the TimeGuard feature, while a value of -1 resets the default recommended value.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setVelocityThreshold(thresh: int, ID: int = -1) int[source]

Adjust the Velocity Threshold of the device (in [m/s]). The 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 BRAKE mode.

Warning

Since the range of threshold values is device dependent, it is recommended NOT to modify factory settings.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setWatchdog(duration: int, ID: int = -1) int[source]

Set the watchdog duration in multiples of 125 microseconds on compatible devices. If the watchdog duration is exceeded before the device recieves a new force command, the device firmware will disable forces.

Parameters:
  • duration (int) – watchdog duration in multiples of 125 us. A value of 0 disables the watchdog feature.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setWristJointTorques(t: Array[int, float], ID: int = -1) int[source]

Set all joint torques of the wrist structure.

Parameters:
  • t (Array[int, float]) – Sequence of (t0, t1, t2) where t0, t1, t2 are the wrist axis torque commands for axes 0, 1, and 2, respectively (in [Nm]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.setWristMotor(output: Array[int, int], ID: int = -1) int[source]

Set desired motor commands to the amplifier channels commanding the WRIST motors.

Parameters:
  • output (Array[int, int]) – Sequence of (output0, output1, output2) where output0, output1, and output2 are the axis 0, 1, and 2 wrist motor commands, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

See also

forcedimension_core.dhd.setMot()
forcedimension_core.dhd.setMotor()
forcedimension_core.dhd.setDeltaMotor()
forcedimension_core.dhd.setGripperMotor()
forcedimension_core.dhd.expert.updateEncoders(ID: int = -1) int[source]

Force an update of the internal encoder values in the state vector. This call retrieves the encoder values from the device and places them into the state vector. No kinematic model is called.

Parameters:

ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:

ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.wristEncoderToOrientation(enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

For devices with a wrist structure, compute the individual angle of each joint, starting with the one located nearest to the wrist base plate.

Note

For the forcedimension_core.constants.DeviceType.OMEGA6_RIGHT and the forcedimension_core.constants.DeviceType.OMEGA6_LEFT devices, angles are computed with respect to their internal reference frame, which is rotated 45 degrees or π/4 radians about the Y axis. Please refer to your device user manual for more information on your device coordinate system.

Note

This feature only applies to devices with a wrist. See the Device Types section for more details.

Parameters:
  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to wrist encoder values on the first, second, and third joint, respectively

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (MutableArray[int, float]) – An output buffer to store the joint angles.

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.wristEncodersToJointAngles(enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

Compute and return the wrist joint angles (in [rad]) for a given set of encoder values.

Parameters:
  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to encoder values on wrist axes 0, 1, and 2, respectively.

  • out (MutableArray[int, float]) – An output buffer to store the joint angles (in [rad]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.wristGravityJointTorques(joint_angles: Array[int, float], out: MutableArray[int, float], ID: int = -1) int[source]

Compute 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.

Deprecated since version 1.0.0: Force Dimension SDK v3.16.0+ recommends that you use forcedimension_core.dhd.jointAnglesToGravityJointTorques() instead.

Parameters:
Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.wristJointAnglesToEncoders(joint_angles: Array[int, float], out: MutableArray[int, int], ID: int = -1) int[source]

Compute and return the wrist encoder values for a given set of wrist joint angles (in [rad]).

Parameters:
  • enc (Array[int, float]) – Sequence of (j0, j1, j1) where j0, j1, and j2 refer to wrist joint angles for axes 0, 1, and 2, respectively, (in [rad]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the raw encoder values.

Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.wristJointAnglesToJacobian(joint_angles: Array[int, float], out: Array[int, MutableArray[int, float]], ID: int = -1) int[source]

Retrieve the 3x3 jacobian matrix for the wrist structure based on a given joint configuration. Please refer to your device user manual for more information on your device coordinate system.

Parameters:
  • joint_angles (Array[int, float]) – Sequence of (j0, j1, j2) where j0, j1, and j2 refer to the joint angles for wrist axis 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (MutableFloatMatrixLike) – An output buffer to store the Jacobian.

Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to a C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

See also

forcedimension_core.dhd.wristEncodersToJointAngles()
forcedimension_core.dhd.getWristJointAngles()
forcedimension_core.dhd.expert.wristJointTorquesExtrema(joint_angles: Array[int, float], minq_out: MutableArray[int, float], maxq_out: MutableArray[int, float], ID: int = -1) int[source]

Compute 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.

Parameters:
Raises:
  • TypeError – If minq_out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(minq_out) < MAX_DOF

  • TypeError – If maxq_out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(maxq_out) < MAX_DOF

  • ctypes.ArgumentError – If any element of joint_angles is not implicitly convertible to C double.

  • IndexError – If len(joint_angles) < 3.

  • TypeError – If joint_angles is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.wristMotorToTorque(output: Array[int, int], enc: Array[int, int], out: MutableArray[int, float], ID: int = -1) int[source]

Compute and return the torque applied to the wrist end-effector for a given set of motor commands at a given orientation (defined by encoder values).

Parameters:
  • cmd (Array[int, int]) – Sequence of (cmd0, cmd1, cmd2) where cmd0, cmd1, and cmd2 are the axis 0, 1, and 2 DELTA motor commands, respectively.

  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to encoder values on axss 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (MutableArray[int, float]) – An output buffer to store the torques applied to the wrist.

Raises:
Returns:

0 on success, -1, otherwise.

forcedimension_core.dhd.expert.wristOrientationToEncoder(orientation: Array[int, float], out: MutableArray[int, int], ID: int = -1) int[source]

For devices with a wrist structure, compute the encoder values from the individual angle of each joint, starting with the one located nearest to the wrist plate base.

Note

For the forcedimension_core.constants.DeviceType.OMEGA6 and forcedimension_core.constants.DeviceType.OMEGA6_LEFT devices, angles must be expressed with respect to their internal reference frame, which is rotated 45 degrees or π/4 radians about the Y axis. Please refer to your device user manual for more information on your device coordinate system.

Note

This feature only applies to devices with a wrist. See the Device Types section for more details.

Parameters:
  • orientation (Array[int, float]) – Sequence of (oa, ob, og) where oa, ob, and og refer to wrist end effector orientation around the X, Y, and Z axes, respectively (in [rad]).

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the encoder values.

Raises:
  • TypeError – If out does not support item assignment either because it’s immutable or not subscriptable.

  • IndexError – If len(out) < 3.

  • ctypes.ArgumentError – If any element of orientation is not implicitly convertible to a C double.

  • IndexError – If len(orientation) < 3.

  • TypeError – If orientation is not subscriptable.

  • ctypes.ArgumentError – If ID is not implicitly convertible to a C char.

Returns:

0 on success, -1 otherwise

forcedimension_core.dhd.expert.wristTorqueToMotor(t: Array[int, float], enc: Array[int, int], out: MutableArray[int, int], ID: int = -1) int[source]

Compute and return the wrist motor commands necessary to obtain a given torque (in [Nm]) on the wrist end-effector at a given orientation (defined by encoder values).

Parameters:
  • t (Array[int, float]) – Sequence of (t0, t1, t2) where t0, t1, and t2 are the DELTA axis torque commands for axes 0, 1, and 2, respectively (in [Nm]).

  • enc (Array[int, int]) – Sequence of (enc0, enc1, enc2) where enc0, enc1, and enc2 refer to encoder values on axes 0, 1, and 2, respectively.

  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (Array[int, int]) – An output buffer to store the wrist motor commands.

Raises:
Returns:

0 on success, -1 otherwise