rby1_sdk.CartesianCommandFeedback#

class CartesianCommandFeedback#

Bases: CommandFeedback

Feedback for a Cartesian command with one or more SE(3) pose targets.

se3_pose_tracking_errors#

Per-target pose tracking errors (position/orientation).

Type:

list[CartesianCommandFeedback.TrackingError]

joint_position_tracking_errors#

Per-joint position tracking errors [rad].

Type:

list[float]

remain_time#

Estimated remaining time to reach targets [s].

Type:

float

manipulability#

Manipulability index (dimensionless).

Type:

float

__init__(self: rby1_sdk.CartesianCommandFeedback) None#

Construct a CartesianCommandFeedback instance.

Methods

__init__(self)

Construct a CartesianCommandFeedback instance.

Attributes

command_header

Header-level feedback.

joint_position_tracking_errors

Per-joint position tracking errors.

manipulability

Manipulability index.

remain_time

Estimated remaining time to reach targets.

se3_pose_tracking_errors

Per-target SE(3) pose tracking errors.

valid

Whether this feedback object contains valid data.

class TrackingError#

Bases: pybind11_object

Per-target SE(3) tracking error.

position_error#

Translational error magnitude [m].

Type:

float

orientation_error#

Rotational error magnitude [rad] (e.g., angle-axis norm).

Type:

float

property orientation_error#
property position_error#
property joint_position_tracking_errors#

Per-joint position tracking errors.

Returns:

Joint-wise position error magnitudes [rad].

Return type:

list[float]

property manipulability#

Manipulability index.

Returns:

Dimensionless manipulability measure (higher is generally better).

Return type:

float

property remain_time#

Estimated remaining time to reach targets.

Returns:

Time remaining [s].

Return type:

float

property se3_pose_tracking_errors#

Per-target SE(3) pose tracking errors.

Returns:

Tracking error objects for each Cartesian target.

Return type:

list[CartesianCommandFeedback.TrackingError]