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.
Note
This feature only applies to the following types of devices:
forcedimension_core.constants.DeviceType.CONTROLLERforcedimension_core.constants.DeviceType.CONTROLLER_HR- Parameters:
devtype (DeviceType) – The device type to use.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
IDis 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)whereenc0,enc1, andenc2refer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C int.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
enc (Array[int, int]) – Sequence of
(enc0, enc1, enc2)whereenc0,enc1, andenc2refer to encoder values on axes 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 return.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C int.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wherefx,fy, andfzare 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)whereenc0,enc1, andenc2refer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If any element of
fis not implicitly convertible to a C char.IndexError – If
len(f) < 3.TypeError – If
fis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.MOTOR_SATURATEDon 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:
joint_angles (Array[int, float]) – Sequence of
(j0, j1, j2)wherej0,j1,j2refer to the joint angles for 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 return.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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:
enc (Array[int, float]) – Sequence of
(j0, j1, j1)wherej0,j1, andj2refer to DELTA joint angles for axes 0, 1, and 2, respectively, (in [rad]).ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the return.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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, andj2refer 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
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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:
joint_angles (Array[int, float]) – Sequence of
(j0, j1, j2)wherej0,j1,j2refer to the joint angles for axes 0, 1, and 2, respectively.ID (int) – Device ID (see Support for Multiple Devices section for details).
minq_out (MutableArray[int, float]) – An output buffer to store the return.
maxq_out (MutableArray[int, float]) – An output buffer to store the return.
- Raises:
TypeError – If
minq_outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(encMin_out) < MAX_DOFTypeError – If
maxq_outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < MAX_DOFctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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)wheremot0,mot1, andmot2are the axis 0, 1, and 2 DELTA motor commands, respectively.enc (Array[int, int]) – Sequence of
(enc0, enc1, enc2)whereenc0,enc1, andenc2refer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If any element of
outputis not implicitly convertible to a C ushort.IndexError – If
len(output) < 3.TypeError – If
outputis not subscriptable.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C char.IndexError – If
len(enc) < 3TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wherepx,py, andpzrefer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If any element of
posis not implicitly convertible to a C double.IndexError – If
len(pos) < 3.TypeError – If
posis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
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
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableFloatMatrixLike) – An output buffer to store the Jacobian.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If any dimension of
outis less than 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < MAX_DOFctypes.ArgumentError – If
maskis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
encmin_out (MutableArray[int, int]) – An output buffer to store the minimum encoder values for each axis.
encmax_out (MutableArray[int, int]) – An output buffer to store the maximum encoder values for each axis.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
TypeError – If one of enc_min_out or enc_max_out either are not subscriptable or do not support item assignment.
IndexError – If either enc_min_out or enc_max_out have length less than
forcedimension_core.constants.MAX_DOFctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the encoder velocities (in [inc/s]).
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < MAX_DOFctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
index (int) – The motor index number as defined by
forcedimension_core.constants.MAX_DOFID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
indexis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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
IDis not implicitly convertible to a C char.- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
jmin_out (MutableArray[int, int]) – An output buffer to store the minimum encoder values for each axis.
jmax_out (MutableArray[int, int]) – An output buffer to store the maximum encoder values for each axis.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
TypeError – If one of jmin_out or jmax_out either are not subscriptable or do not support item assignment.
IndexError – If either jmin_out or jmax_out have length less than
forcedimension_core.constants.MAX_DOFctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the joint angles (in [rad]).
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < MAX_DOFctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon success, -1 otherwise.
See also
- 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the joint velocities (in [rad/s]).
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < MAX_DOFctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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
IDis 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
IDis 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (Array[int, int]) – An output buffer to store the raw wrist encoder values.
- Raises:
ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the Jacobian.
- Raises:
TypeError – If
outdoes 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
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the wrist joint angles.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
angle (float) – Gripper opening as an angle (in [rad]).
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
angleis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If
encis not implicitly convertible to a C char.IndexError – If
len(enc) < 3ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.TIMEGUARDon 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:
ctypes.ArgumentError – If
encis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
- Raises:
ctypes.ArgumentError – If
fis not implicitly convertible to a C double.ctypes.ArgumentError – If any member of
enc_wristis not implicitly convertible to a C ushort.IndexError – If
len(enc_wrist) < 3.TypeError – If
enc_wristis not subscriptable.ctypes.ArgumentError – If
enc_gripperis not implicitly convertible to a C ushort.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 or
forcedimension_core.constants.MOTOR_SATURATEDon 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
gapis not implicitly convertible to a C char.- raises ctypes.ArgumentError:
If
IDis 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)whereenc0,enc1,enc2are 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:
ctypes.ArgumentError – If
cmdis not implicitly convertible to a C ushort.ctypes.ArgumentError – If any element of
enc_wristis not implicitly convertible to a C int.IndexError – If
len(enc_wrist) < 3.TypeError – If
enc_wristis not subscriptable.ctypes.ArgumentError – If
enc_gripperis not implicitly convertible to a C int.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If
joint_anglesis not implicitly convertible to a C char.IndexError – If
len(joint_angles) < forcedimension_core.constants.MAX_DOF.TypeError – If
joint_anglesis not subscriptable.TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out)is less thanforcedimension_core.constants.MAX_DOF.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.ctypes.ArgumentError – If
maskis not implicitly convertible to a C uchar.
- 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:
ID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableFloatMatrixLike) – Output buffer for the inertia matrix.
- Raises:
ctypes.ArgumentError – If
joint_anglesis not implicitly convertible to a C char.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If of the any dimension of
outis less than 6.ctypes.ArgumentError – If
IDis 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 callingforcedimension_core.dhd.setForce()and the friends.- Parameters:
- Raises:
ctypes.ArgumentError – If any element of
cmdsis not implicitly convertible to a C ushort.IndexError – If
len(cmds) < MAX_DOF.TypeError – If
cmdsis not subscriptable.ctypes.ArgumentError – If
maskis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
val (Array[int, int]) – Vector of encoder offsets refering to each DOF with length
forcedimension_core.constants.MAX_DOF.mask (int) – Bitwise mask of which encoder should be set.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
valis not implicitly convertible to a C char.IndexError – If
len(val) < MAX_DOF.TypeError – If
valis not subscriptable.ctypes.ArgumentError – If
maskis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
filename (bytes) – Configuration file containing device calibration/configuration data.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
IDis 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:
ctypes.ArgumentError – If
maskis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
mode (ComMode) – desired COM operation mode.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
modeis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wheret0,t1, andt2are the DELTA axis torque commands for axes 0, 1, and 2, respectively (in [Nm]).- Raises:
ctypes.ArgumentError – If any element of
tis not implicitly convertible to a C char.IndexError – If
len(t) < 3.TypeError – If
tis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wheremot0,mot1, andmot2are the axis 0, 1, and 2 DELTA motor commands, respectively.ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If any element of
motis not implicitly convertible to a C ushort.IndexError – If
len(mot) < 3.TypeError – If
motis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wherefx,fy, andfzare 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,t2are 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:
ctypes.ArgumentError – If any element of
fis not implicitly convertible to a C double.IndexError – If
len(f) < 3.TypeError – If
fis not subscriptable.ctypes.ArgumentError – If any element of
tis not implicitly convertible to a C double.IndexError – If
len(t) < 3.TypeError – If
tis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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)wherefx,fy, andfzare 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,t2are 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:
ctypes.ArgumentError – If any element of
fis not implicitly convertible to a C double.IndexError – If
len(f) < 3.TypeError – If
fis not subscriptable.ctypes.ArgumentError – If any element of
tis not implicitly convertible to a C double.IndexError – If
len(t) < 3.TypeError – If
tis not subscriptable.ctypes.ArgumentError – If
gripper_forceis not implicitly convertible to a C double.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
output (int) – Gripper motor command.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
outputis not implicitly convertible to a C ushort.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If any element of
cmdsis not implicitly convertible to a C double.IndexError – If
len(q) < MAX_DOF.TypeError – If
qis not subscriptable.ctypes.ArgumentError – If
maskis not implicitly convertible to a C uchar.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If any element of
cmdsis not implicitly convertible to a C ushort.IndexError – If
len(cmds) < MAX_DOF.TypeError – If
cmdsis not subscriptable.ctypes.ArgumentError – If
maskis not implicitly convertible to a C uchar.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
index (int) – The motor index number as defined by
forcedimension_core.constants.MAX_DOFoutput (int) – The motor DAa C char.
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
indexis not implicitly convertible to a C char.ctypes.ArgumentError – If
outputis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If
min_periodis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
thresh (int) – An arbitrary value of velocity threshold (in [m/s]).
ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If
threshis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If
durationis not implicitly convertible to a C char.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
ctypes.ArgumentError – If any element of
tis not implicitly convertible to a C double.IndexError – If
len(t) < 3.TypeError – If
tis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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.
Note
This feature only applies to the following devices:
forcedimension_core.constants.DeviceType.SIGMA7_RIGHTforcedimension_core.constants.DeviceType.SIGMA7_LEFT- Parameters:
output (Array[int, int]) – Sequence of (output0, output1, output2) where
output0,output1, andoutput2are the axis 0, 1, and 2 wrist motor commands, respectively.ID (int) – Device ID (see Support for Multiple Devices section for details).
- Raises:
ctypes.ArgumentError – If any element of
outputis not implicitly convertible to a C char.IndexError – If
len(output) < 3.TypeError – If
outputis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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
IDis 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_RIGHTand theforcedimension_core.constants.DeviceType.OMEGA6_LEFTdevices, 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)whereenc0,enc1, andenc2refer to wrist encoder values on the first, second, and third joint, respectivelyID (int) – Device ID (see Support for Multiple Devices section for details).
out (MutableArray[int, float]) – An output buffer to store the joint angles.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C char.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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, andenc2refer 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:
ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C int.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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:
joint_angles (Array[int, float]) – Sequence of
(j0, j1, j2)wherej0,j1, andj2refer to the joint angles for wrist axes 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 joint torques.
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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:
- Raises:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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)wherej0,j1, andj2refer 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
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to a C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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:
joint_angles (Array[int, float]) – Sequence of
(j0, j1, j2)wherej0,j1,j2refer to the joint angles for wrist axes 0, 1, and 2, respectively.ID (int) – Device ID (see Support for Multiple Devices section for details).
minq_out (MutableArray[int, float]) – An output buffer to store the return.
maxq_out (MutableArray[int, float]) – An output buffer to store the return.
- Raises:
TypeError – If
minq_outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(minq_out) < MAX_DOFTypeError – If
maxq_outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(maxq_out) < MAX_DOFctypes.ArgumentError – If any element of
joint_anglesis not implicitly convertible to C double.IndexError – If
len(joint_angles) < 3.TypeError – If
joint_anglesis not subscriptable.ctypes.ArgumentError – If
IDis 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).
Note
This feature only applies to the following devices:
forcedimension_core.constants.DeviceType.SIGMA7_RIGHTforcedimension_core.constants.DeviceType.SIGMA7_LEFT- Parameters:
cmd (Array[int, int]) – Sequence of
(cmd0, cmd1, cmd2)wherecmd0,cmd1, andcmd2are the axis 0, 1, and 2 DELTA motor commands, respectively.enc (Array[int, int]) – Sequence of
(enc0, enc1, enc2)whereenc0,enc1, andenc2refer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
cmdis not implicitly convertible to a C ushort.IndexError – If
len(cmd) < 3.TypeError – If
cmdis not subscriptable.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C char.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- 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.OMEGA6andforcedimension_core.constants.DeviceType.OMEGA6_LEFTdevices, 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)whereoa,ob, andogrefer 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
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
orientationis not implicitly convertible to a C double.IndexError – If
len(orientation) < 3.TypeError – If
orientationis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 on success, -1 otherwise
See also
forcedimension_core.dhd.expert.wristEncodersToOrientation()
- 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).
Note
This feature only applies to the following devices:
forcedimension_core.constants.DeviceType.SIGMA7_RIGHTforcedimension_core.constants.DeviceType.SIGMA7_LEFT- Parameters:
t (Array[int, float]) – Sequence of
(t0, t1, t2)wheret0,t1, andt2are the DELTA axis torque commands for axes 0, 1, and 2, respectively (in [Nm]).enc (Array[int, int]) – Sequence of
(enc0, enc1, enc2)whereenc0,enc1, andenc2refer 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:
TypeError – If
outdoes not support item assignment either because it’s immutable or not subscriptable.IndexError – If
len(out) < 3.ctypes.ArgumentError – If any element of
tis not implicitly convertible to a C double.IndexError – If
len(t) < 3.TypeError – If
tis not subscriptable.ctypes.ArgumentError – If any element of
encis not implicitly convertible to a C int.IndexError – If
len(enc) < 3.TypeError – If
encis not subscriptable.ctypes.ArgumentError – If
IDis not implicitly convertible to a C char.
- Returns:
0 on success, -1 otherwise