rby1_sdk.RobotState_A#

class RobotState_A#

Bases: pybind11_object

Robot state information.

Provides information about the overall state of the robot, including system statistics, battery state, power states, emergency stop button states, joint states, tool flange states, force/torque sensor data, and odometry.

timestamp#

Timestamp of the robot state (system clock).

Type:

datetime.datetime

system_stat#

System statistics (CPU, memory, uptimes).

Type:

SystemStat

battery_state#

Battery voltage/current/level.

Type:

BatteryState

power_states#

Power supply states for each module.

Type:

list of PowerState

emo_states#

Emergency-stop button states for each module.

Type:

list of EMOState

joint_states#

Per-joint status and measurements.

Type:

list of JointState

tool_flange_right#

Tool flange sensor and IO state for the right arm.

Type:

ToolFlangeState

tool_flange_left#

Tool flange sensor and IO state for the left arm.

Type:

ToolFlangeState

ft_sensor_right#

Force/torque readings on the right arm.

Type:

FTSensorData

ft_sensor_left#

Force/torque readings on the left arm.

Type:

FTSensorData

is_ready#

Whether each joint is ready.

Type:

numpy.ndarray of bool, shape (DOF,)

position#

Joint positions [rad].

Type:

numpy.ndarray, shape (DOF,)

velocity#

Joint velocities [rad/s].

Type:

numpy.ndarray, shape (DOF,)

current#

Joint currents [A].

Type:

numpy.ndarray, shape (DOF,)

torque#

Joint torques in Nm.

Type:

numpy.ndarray, shape (DOF,)

target_position#

Target joint positions [rad].

Type:

numpy.ndarray, shape (DOF,)

target_velocity#

Target joint velocities [rad/s].

Type:

numpy.ndarray, shape (DOF,)

target_feedback_gain#

Target feedback gains per joint. Range is [0, 10].

Type:

numpy.ndarray, shape (DOF,)

target_feedforward_torque#

Target feedforward torques per joint in Nm.

Type:

numpy.ndarray, shape (DOF,)

odometry#

Base pose as a 2D homogeneous transform (SE(2)): rotation (R) and translation (t).

Type:

numpy.ndarray, shape (3, 3)

center_of_mass#

Center of mass position in base frame in meters.

Type:

numpy.ndarray, shape (3,)

collisions#

Detected collisions or nearest link pairs (links, closest points, signed distance).

Type:

list of CollisionResult

temperature#

Joint temperatures in degrees Celsius.

Type:

numpy.ndarray, shape (DOF,)

gravity#

Gravity compensation torques per joint in Nm.

Type:

numpy.ndarray, shape (DOF,)

Notes

Unless noted otherwise, joint-wise vectors are NumPy arrays with shape (DOF,), where DOF = robot.model().robot_dof. odometry uses a 2D homogeneous transform (SE(2)). signed distance is negative when penetrating.

__init__(self: rby1_sdk.RobotState_A) None#

Construct a RobotState instance.

Methods

__init__(self)

Construct a RobotState instance.

Attributes

property battery_state#
property center_of_mass#
property collisions#
property current#
property emo_states#
property ft_sensor_left#
property ft_sensor_right#
property gravity#
property is_ready#
property joint_states#
property odometry#
property position#
property power_states#
property system_stat#
property target_feedback_gain#
property target_feedforward_torque#
property target_position#
property target_velocity#
property temperature#
property timestamp#
property tool_flange_left#
property tool_flange_right#
property torque#
property velocity#