feathersdk.robot.torso_platform Module¶
- class feathersdk.robot.torso_platform.EZMotionCommands(*values)¶
Bases:
EnumEZMotion CANopen command addresses.
- GET_CURRENT_CURRENT = 24696¶
- GET_CURRENT_POSITION = 24676¶
- GET_CURRENT_TORQUE = 24695¶
- GET_CURRENT_VELOCITY = 24684¶
- GET_ERROR_REGISTER = 8203¶
- GET_STATUS_WORD = 24641¶
- GET_TEMPERATURE = 8256¶
- HOMING_ACCELERATION = 24730¶
- HOMING_METHOD = 24728¶
- HOMING_OFFSET = 24700¶
- HOMING_SPEED = 24729¶
- MAX_TORQUE = 24690¶
- SET_CONTROL_MODE = 24672¶
- SET_MAX_ACCELERATION = 24707¶
- SET_MAX_DECELERATION = 24708¶
- SET_MAX_HOMING_TORQUE = 8304¶
- SET_MAX_VELOCITY = 24705¶
- SET_OPERATION_STATE = 24640¶
- SET_POSITION = 24698¶
- SET_VELOCITY = 24831¶
- class feathersdk.robot.torso_platform.EZMotionControlMode(*values)¶
Bases:
EnumEZMotion motor control modes.
- HOMING = 6¶
- POSITION = 1¶
- VELOCITY = 3¶
- class feathersdk.robot.torso_platform.EZMotionHomingMethod(*values)¶
Bases:
EnumEZMotion homing methods.
- HOME_USING_MAX_TORQUE_DOWN = -2¶
- HOME_USING_MAX_TORQUE_UP = -3¶
- class feathersdk.robot.torso_platform.EZMotionMotor(motor_id: int, can_interface: str, motor_name: str, config: dict)¶
Bases:
MotorEZMotion motor representation.
- __init__(motor_id: int, can_interface: str, motor_name: str, config: dict)¶
Initialize EZMotion motor.
- Parameters:
motor_id (int) – CAN node ID of the motor
can_interface (str) – CAN interface name
motor_name (str) – Name identifier for the motor
config (dict) – Motor configuration with optional keys: - default_target_velocity_rps: Default target velocity in rotations per second - default_target_acceleration_rps2: Default acceleration in rotations per second squared - default_target_deceleration_rps2: Default deceleration in rotations per second squared
- class feathersdk.robot.torso_platform.EZMotionOperationState(*values)¶
Bases:
EnumEZMotion motor operation states.
- ENABLED = 15¶
- SHUTDOWN = 6¶
- TRANSITION_TO_NEW_POSITION = 31¶
- class feathersdk.robot.torso_platform.EZMotionTorsoPlatform(motors_manager: MotorsManager, power: BatterySystem, can_interface: str | None, config: dict)¶
Bases:
TorsoPlatformEZMotion-based torso platform implementation.
- __init__(motors_manager: MotorsManager, power: BatterySystem, can_interface: str | None, config: dict)¶
Initialize EZMotion torso platform.
- Parameters:
motors_manager (MotorsManager) – Manager for motor communication
power (BatterySystem) – Battery system for power event handling
can_interface (Optional[str]) – CAN interface name, or None to skip CAN initialization
config (dict) – Configuration dictionary with required “motors” key and optional keys: - top_height_mm: Maximum height in millimeters (default: 600) - bottom_height_mm: Minimum height in millimeters (default: 50) - homing_offset_from_top_num_rotations: Homing offset from top in rotations (default: 1) - homing_max_torque_percent: Maximum torque for homing in percent (default: 1000) - homing_acceleration: Homing acceleration in rotations per second squared (default: 50) - print_packet_loss: If True, print packet loss warnings (default: False) - show_all_sdo_errors: If True, show all SDO errors (default: True)
- Raises:
Exception – If power cycle detected and system must be recalibrated
- calc_max_height_target_position(associated_height: float, associated_position: int)¶
Calculate maximum height target position.
- Parameters:
associated_height (float) – Reference height in millimeters
associated_position (int) – Reference position in motor steps
- Returns:
Maximum height target position in motor steps
- Return type:
int
- calc_min_height_target_position(associated_height: float, associated_position: int)¶
Calculate minimum height target position.
- Parameters:
associated_height (float) – Reference height in millimeters
associated_position (int) – Reference position in motor steps
- Returns:
Minimum height target position in motor steps
- Return type:
int
- canopen_thread_main(node: RemoteNode)¶
- clear_errors()¶
Clear motor errors.
- enable()¶
Enable motor operation.
- enable_velocity_mode()¶
Enable velocity control mode and set velocity to zero.
- get_current_position()¶
Get current motor position.
- Returns:
Current position in motor steps, or False if read failed
- Return type:
int | bool
- get_current_position_with_retry()¶
Get current position with retry logic.
- Returns:
Current position in motor steps
- Return type:
int
- Raises:
Exception – If position cannot be read after retries
- get_current_torque()¶
Get current motor torque.
- Returns:
Current torque value, or False if read failed
- Return type:
int | bool
- get_current_velocity()¶
Get current motor velocity.
- Returns:
Current velocity in steps per second, or False if read failed
- Return type:
int | bool
- get_state()¶
Get current motor state.
- Returns:
Dictionary with keys: temperature, velocity, torque, position, height
- Return type:
dict
- get_status_word()¶
Get motor status word.
- Returns:
Status word value, or False if read failed
- Return type:
int | bool
- go_to(height_from_bottom: float)¶
Move to target height from bottom.
- Parameters:
height_from_bottom (float) – Target height in millimeters from bottom
- Raises:
Exception – If system not healthy or height is outside valid range
- has_error()¶
Check if motor has error.
- health_check()¶
Perform health check on motor.
- Returns:
Dictionary with keys: temperature, current, position
- Return type:
dict
- init_ezmotion()¶
Initialize EZMotion motor to position control mode.
- on_abort()¶
- on_fork()¶
- on_power_event(event: PowerEvent)¶
Handle power system events.
- Parameters:
event (PowerEvent) – The power event type (POWER_OFF or POWER_RESTORED)
- recalibrate()¶
Recalibrate torso by homing to top position.
- send_movement_profile(target_velocity=None, target_acceleration=None, target_deceleration=None)¶
Send movement profile parameters to motor (only if changed).
- Parameters:
target_velocity (float, optional) – Target velocity in rotations per second
target_acceleration (float, optional) – Target acceleration in rotations per second squared
target_deceleration (float, optional) – Target deceleration in rotations per second squared
- set_control_mode(control_mode: EZMotionControlMode)¶
Set motor control mode.
- Parameters:
control_mode (EZMotionControlMode) – Control mode to set
- set_movement_profile(target_velocity, target_acceleration, target_deceleration)¶
Set movement profile parameters for the motor.
- Parameters:
target_velocity (float, optional) – Target velocity in rotations per second
target_acceleration (float, optional) – Target acceleration in rotations per second squared
target_deceleration (float, optional) – Target deceleration in rotations per second squared
- shutdown()¶
Shutdown motor and stop movement.
- transition_to_new_position()¶
Transition motor to new position state.
- update_relative(delta_mm: float, velocity: float | None = None)¶
Update position by delta_mm relative to current position. Will clamp final position to be within valid range.
- Parameters:
delta_mm (float) – Delta height in millimeters from current position
velocity (float) – Velocity in millimeters per second [0, 200] mm/s, or None to use motor default
- update_velocity(mm_per_second: float, skip_overwrite: bool = False)¶
Update torso velocity in velocity control mode.
- Parameters:
mm_per_second (float) – Velocity in millimeters per second, range -200 to 200
skip_overwrite (bool) – If True, skip overwriting calibration file
- Raises:
Exception – If system not healthy or velocity exceeds maximum
- wait_for_recalibration()¶
Wait for recalibration to complete.
- class feathersdk.robot.torso_platform.TorsoPlatform¶
Bases:
SteppableSystemBase class for torso platform control.
- __init__()¶
Initialize torso platform.
- async get_position()¶
- async get_state()¶
- go_to(height_from_bottom: float)¶
- async health_check()¶
- recalibrate()¶
- set_movement_profile(target_velocity, target_acceleration, target_jerk)¶
- feathersdk.robot.torso_platform.overwrite_file(filepath: str, data: list)¶
Overwrite file with comma-separated data.
- Parameters:
filepath (str) – Path to the file to overwrite
data (list) – List of strings to write as comma-separated values
- feathersdk.robot.torso_platform.read_array_from_file(filepath: str)¶
Read comma-separated values from file.
- Parameters:
filepath (str) – Path to the file to read
- Returns:
List of strings read from the file
- Return type:
list