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.