forcedimension_core.dhd.expert.direct module

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

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

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

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

This routine computes and returns the DELTA joint angles (in [rad]) for a given set of encoder values.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

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

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

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 axis 0, 1, and 2, respectively.

  • out (SupportsPtrs3[ctypes.c_ushort]) – An output buffer to store the motor commands on axes 0, 1, and 2.

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

Raises:
Returns:

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

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

This routine computes and returns the DELTA encoder values for a given set of joint angles (in [rad]).

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.deltaJointAnglesToJacobian(joint_angles: Array[int, float], out: SupportsPtr[c_double], 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 (in [rad]) for axis 0, 1, and 2, respectively.

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

  • out (SupportsPtr[c_double]) – An output buffer to store the Jacobian.

Raises:
Returns:

0 on success, -1 otherwise.

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

Compute the range of applicable DELTA joint torques (in [Nm]) for a given DELTA joint angle configuration (in [rad]). 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 (in [rad]) for axis 0, 1, and 2, respectively.

  • minq_out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the minimum appliable DELTA joint torques about axes 0, 1, and 2 (in [Nm]).

  • maxq_out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the maximum appliable DELTA joint torques about axes 0, 1, and 2 (in [Nm]).

Raises:
Returns:

0 on success, -1 otherwise.

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

This routine computes and returns the force applied to the end-effector about the X, Y, and Z axes (in [N]) 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.

  • out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the force applied to the end effector about the X, Y, and Z axes (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.direct.deltaPositionToEncoder(pos: Array[int, float], out: SupportsPtrs3[c_int], ID: int = -1) int[source]

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

Parameters:
Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.getDeltaEncoders(out: SupportsPtrs3[c_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.direct.getDeltaJacobian(out: SupportsPtr[c_double], 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:
Returns:

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

forcedimension_core.dhd.expert.direct.getDeltaJointAngles(out: SupportsPtrs3[c_double], ID: int = -1) int[source]

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

Parameters:
Raises:
Returns:

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

forcedimension_core.dhd.expert.direct.getEnc(out: SupportsPtr[c_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:
Returns:

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

forcedimension_core.dhd.expert.direct.getEncVelocities(out: SupportsPtr[c_double], ID: int = -1) int[source]

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

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

  • out (SupportsPtr[c_double]) – An output buffer to store the encoder velocities (in [inc/s]) for all sensed degrees-of-freedom of the current device.

Raises:
Returns:

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

forcedimension_core.dhd.expert.direct.getJointAngles(out: SupportsPtr[c_double], ID: int = -1) int[source]

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

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

  • out (SupportsPtr[c_double]) – An output buffer to store the joint angles (in [rad]) for all sensed degrees-of-freedom for the current device.

Raises:
Returns:

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

forcedimension_core.dhd.expert.direct.getJointVelocities(out: SupportsPtr[c_double], ID: int = -1) int[source]

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

Parameters:

out (SupportsPtr[c_double]) – An output buffer to store the joint velocities (in [rad/s]) for all sensed degrees-of-freedom of the current device.

Raises:
Returns:

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

forcedimension_core.dhd.expert.direct.getWristEncoders(out: SupportsPtrs3[c_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.direct.getWristJacobian(out: SupportsPtr[c_double], 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:
Returns:

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

forcedimension_core.dhd.expert.direct.getWristJointAngles(out: SupportsPtrs3[c_double], ID: int = -1) int[source]

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

Parameters:
Raises:
Returns:

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

See also

forcedimension_core.dhd.expert.direct.dhdWristJointAnglesToJacobian()
forcedimension_core.dhd.expert.direct.dhdWristJointTorquesExtrema()
forcedimension_core.dhd.expert.direct.gripperForceToMotor(f: float, enc_wrist_grip: SupportsPtr[c_int], out: c_ushort, ID: int = -1) Tuple[int, int][source]

Given a desired force to be displayed by the force gripper, this routine computes and returns the refering motor command.

Note

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

Parameters:
Raises:
Returns:

A tuple in the form (cmd, err). cmd is the motor command on the gripper axis. err is 0 or forcedimension_core.constants.MOTOR_SATURATED on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.gripperMotorToForce(cmd: int, enc_wrist_grip: SupportsPtr[c_int], out: c_double, ID: int = -1) int[source]

Computes the force applied to the end-effector (in [N]) 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_grip (SupportsPtr[c_int]) – Buffer which contains the encoder values about wrist joints 0, 1, and 2 as well as the encoder value of the gripper.

  • out (c_ushort) – 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.direct.jointAnglesToGravityJointTorques(joint_angles: SupportsPtr[c_double], out: SupportsPtr[c_double], 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.

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

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

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.jointAnglesToIntertiaMatrix(joint_angles: SupportsPtr[c_double], out: SupportsPtr[c_double], 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:
  • ID (int) – Device ID (see Support for Multiple Devices section for details).

  • out (SupportsPtr[c_double]) – An array of joint angles (in [rad]) containing joint angles for all degrees of freedom.

  • out – An output buffer for the 6x6 inertia matrix.

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.preloadMot(cmds: SupportsPtr[c_ushort], 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

See also

forcedimension_core.containers.DOFMot
forcedimension_core.containers.numpy.DOFMot
forcedimension_core.dhd.expert.direct.setJointTorques(q: SupportsPtr[c_double], mask: int = 255, ID: int = -1)[source]

Sets all joint torques on all active axes.

Parameters:
  • q (SupportsPtr[c_double]) – An input buffer to store the Joint torques for each degree-of-freedom (in [Nm]).

  • mask (int) – Bitwise mask of which joints should be set

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

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.setMot(cmds: SupportsPtr[c_ushort], 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.direct.wristEncoderToOrientation(enc: Array[int, int], out: SupportsPtrs3[c_double], ID: int = -1) int[source]

For devices with a wrist structure, compute the individual angle of each joint (in [rad]), starting with the one located nearest to the wrist base plate. For the forcedimension_core.constants.DeviceType.OMEGA6 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

  • out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the wrist end-effector orientation about the first, second, and third wrist joints (in [rad]).

Raises:
Returns:

0 on success, -1 otherwise.

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

This routine computes and returns 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 (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the joint angles (in [rad]) about wrist joint axes 0, 1, and 2.

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

Raises:
Returns:

0 on success, -1 otherwise.

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

This routine computes and returns 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 (in [rad]) for axes 0, 1, and 2, respectively.

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

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

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.wristJointAnglesToJacobian(joint_angles: Array[int, float], out: SupportsPtr[c_double], 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.

  • out (SupportsPtr[c_double]) – An output buffer to store the wrist jacobian.

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

Raises:
Returns:

0 on success, -1 otherwise.

forcedimension_core.dhd.expert.direct.wristJointTorquesExtrema(joint_angles: Array[int, float], minq_out: SupportsPtr[c_double], maxq_out: SupportsPtr[c_double], 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:
  • joint_angles (Array[int, float]) – Sequence of (j0, j1, j2) where j0, j1, j2 refer to the joint angles for wrist axes 0, 1, and 2, respectively.

  • minq_out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the minimum appliable DELTA joint torques about axes 0, 1, and 2 (in [Nm]).

  • maxq_out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the maximum appliable DELTA joint torques about axes 0, 1, and 2 (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.direct.wristMotorToTorque(output: Array[int, int], enc: Array[int, int], out: SupportsPtrs3[c_double], ID: int = -1) int[source]

This routine computes and returns the torque applied to the wrist end-effector about the, X, Y, and Z axes (in [Nm]) for a given set of motor commands at a given orientation (defined by encoder values)

Note

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

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 axis 0, 1, and 2, respectively.

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

  • out (SupportsPtrs3[ctypes.c_double]) – An output buffer to store the torques applied to the wrist about the X, Y, and Z axes (in [Nm]).

Raises:
Returns:

0 on success, -1, otherwise.

forcedimension_core.dhd.expert.direct.wristOrientationToEncoder(orientation: Array[int, float], out: SupportsPtrs3[c_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 an wrist. See the Device Types section for more details.

Parameters:
Raises:
Returns:

0 on success, -1 otherwise

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

This routine computes and returns the wrist motor commands necessary to obtain a given torque on the wrist end-effector about the X, Y, and Z axes (in [Nm]) 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 (in [Nm]) for axes 0, 1, and 2, 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.

  • out (SupportsPtrs3[ctypes.c_ushort]) – An output buffer to store the wrist motor commands.

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

Raises:
Returns:

0 on success, -1 otherwise