toddlerbot.actuation package¶
Submodules¶
toddlerbot.actuation.dynamixel_client module¶
Communication using the DynamixelSDK.
- class toddlerbot.actuation.dynamixel_client.DynamixelClient(motor_ids: Sequence[int], port: str = '/dev/ttyUSB0', baudrate: int = 1000000, lazy_connect: bool = False)¶
Bases:
object
Client for communicating with Dynamixel motors.
NOTE: This only supports Protocol 2.
- OPEN_CLIENTS: Set[Any] = {}¶
- bulk_read(attr_list: List[str], retries: int) Tuple[float, Dict[str, ndarray[Any, dtype[float32]]]] ¶
Reads values from a group of motors.
- Parameters:
motor_ids – The motor IDs to read from.
address – The control table address to read from.
size – The size of the control table value being read.
- Returns:
The values read from the motors.
- check_connected()¶
Ensures the robot is connected.
- connect()¶
Connects to the Dynamixel motors.
- NOTE: This should be called after all DynamixelClients on the same
process are created.
- convert_to_unsigned(value: int, size: int) int ¶
Converts the given value to its unsigned representation.
- disconnect()¶
Disconnects from the Dynamixel device.
- get_cur_scale(retries: int = 0) ndarray[Any, dtype[float32]] ¶
Returns the current scale for the motors.
- handle_packet_result(comm_result: int, dxl_error: int | None = None, dxl_id: int | None = None, context: str | None = None)¶
Handles the result from a communication request.
- property is_connected: bool¶
- read_cur(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Returns the current positions and velocities.
- read_model_number(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Returns the model number of the motors.
- read_pos(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Returns the current positions and velocities.
- read_pos_vel(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]], ndarray[Any, dtype[float32]]] ¶
Returns the current positions and velocities.
- read_pos_vel_cur(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]], ndarray[Any, dtype[float32]], ndarray[Any, dtype[float32]]] ¶
Returns the current positions and velocities.
- read_vel(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Returns the current positions and velocities.
- read_vin(retries: int = 0) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Reads the input voltage to the motors.
- reboot(motor_ids: Sequence[int])¶
Reboots the specified motors.
- Parameters:
motor_ids (Sequence[int]) – A sequence of motor IDs to reboot.
- set_torque_enabled(motor_ids: Sequence[int], enabled: bool, retries: int = -1, retry_interval: float = 0.25)¶
Sets whether torque is enabled for the motors.
- Parameters:
motor_ids – The motor IDs to configure.
enabled – Whether to engage or disengage the motors.
retries – The number of times to retry. If this is <0, will retry forever.
retry_interval – The number of seconds to wait between retries.
- sync_read(address: int, size: int, scale: float) Tuple[float, ndarray[Any, dtype[float32]]] ¶
Reads values from a group of motors.
- Parameters:
motor_ids – The motor IDs to read from.
address – The control table address to read from.
size – The size of the control table value being read.
- Returns:
The values read from the motors.
- sync_write(motor_ids: Sequence[int], values: Sequence[Any], address: int, size: int)¶
Writes values to a group of motors.
- Parameters:
motor_ids – The motor IDs to write to.
values – The values to write.
address – The control table address to write to.
size – The size of the control table value being written to.
- write_byte(motor_ids: Sequence[int], value: int, address: int) Sequence[int] ¶
Writes a value to the motors.
- Parameters:
motor_ids – The motor IDs to write to.
value – The value to write to the control table.
address – The control table address to write to.
- Returns:
A list of IDs that were unsuccessful.
- write_desired_cur(motor_ids: Sequence[int], currents: ndarray[Any, dtype[float32]])¶
Writes the given desired currents.
- Parameters:
motor_ids – The motor IDs to write to.
currents – The currents to write.
- write_desired_pos(motor_ids: Sequence[int], positions: ndarray[Any, dtype[float32]])¶
Writes the given desired positions.
- Parameters:
motor_ids – The motor IDs to write to.
positions – The joint angles in radians to write.
- toddlerbot.actuation.dynamixel_client.dynamixel_cleanup_handler()¶
Handles cleanup of open Dynamixel clients by forcibly closing active connections.
Iterates over all open Dynamixel clients and checks if their port handlers are in use. If a port handler is active, logs a warning message and forces the client to close by setting the port handler’s is_using attribute to False and disconnecting the client.
- toddlerbot.actuation.dynamixel_client.signed_to_unsigned(value: int, size: int) int ¶
Converts a signed integer to its unsigned equivalent based on the specified size.
- Parameters:
value (int) – The signed integer to convert.
size (int) – The size in bytes of the integer type.
- Returns:
The unsigned integer representation of the input value.
- Return type:
int
- toddlerbot.actuation.dynamixel_client.unsigned_to_signed(value: int, size: int) int ¶
Converts an unsigned integer to a signed integer of a specified byte size.
- Parameters:
value (int) – The unsigned integer to convert.
size (int) – The byte size of the integer.
- Returns:
The signed integer representation of the input value.
- Return type:
int
toddlerbot.actuation.dynamixel_control module¶
- class toddlerbot.actuation.dynamixel_control.DynamixelConfig(port: str, baudrate: int, control_mode: List[str], kP: List[float], kI: List[float], kD: List[float], kFF2: List[float], kFF1: List[float], init_pos: List[float], default_vel: float = 3.141592653589793, interp_method: str = 'cubic', return_delay_time: int = 1)¶
Bases:
object
Data class for storing Dynamixel configuration parameters.
- baudrate: int¶
- control_mode: List[str]¶
- default_vel: float = 3.141592653589793¶
- init_pos: List[float]¶
- interp_method: str = 'cubic'¶
- kD: List[float]¶
- kFF1: List[float]¶
- kFF2: List[float]¶
- kI: List[float]¶
- kP: List[float]¶
- port: str¶
- return_delay_time: int = 1¶
- class toddlerbot.actuation.dynamixel_control.DynamixelController(config: DynamixelConfig, motor_ids: List[int])¶
Bases:
BaseController
Class for controlling Dynamixel motors.
- close_motors()¶
Closes all active Dynamixel motor clients.
This method iterates over all currently open Dynamixel clients and forces them to close if they are in use. It logs a message for each client that is being forcibly closed and then sets the client’s port handler to not in use before disconnecting the client.
- connect_to_client(latency_value: int = 1)¶
Connects to a Dynamixel client and sets the USB latency timer.
This method sets the USB latency timer for the specified port and attempts to connect to a Dynamixel client. The latency timer is set differently based on the operating system. If the connection fails, an error is logged or raised.
- Parameters:
latency_value (int) – The desired latency timer value. Defaults to 1.
- Raises:
ConnectionError – If the connection to the Dynamixel port fails.
- disable_motors(ids=None)¶
Disables the torque for specified motors or all motors if no IDs are provided.
- Parameters:
ids (list, optional) – A list of motor IDs to disable. If None, all motors will be disabled.
- enable_motors(ids=None)¶
Enables torque for specified motors or all motors if no IDs are provided.
- Parameters:
ids (list, optional) – A list of motor IDs to enable. If None, all motors will be enabled.
- get_motor_state(retries: int = 0) Dict[int, JointState] ¶
Retrieves the current state of the motors, including position, velocity, and current.
- Parameters:
retries (int) – The number of retry attempts for reading motor data in case of failure. Defaults to 0.
- Returns:
A dictionary mapping motor IDs to their respective JointState, which includes time, position, velocity, and torque.
- Return type:
Dict[int, JointState]
- initialize_motors()¶
Initialize the motors by rebooting, checking voltage, and configuring settings.
This method performs the following steps: 1. Reboots the motors. 2. Checks the input voltage to ensure it is above a safe threshold. 3. Configures various motor settings such as return delay time, control mode, and PID gains. 4. Enables torque on the motors.
- Raises:
ValueError – If the input voltage is below 10V, indicating a potential power supply issue.
- set_cur(cur: List[float])¶
Sets the desired current for the motors.
This method writes the specified current values to the motors identified by motor_ids. The operation is thread-safe, ensuring that the current values are set without interference from other threads.
- Parameters:
cur (List[float]) – A list of current values to be set for the motors.
- set_kp(kp: List[float])¶
Set the proportional gain (Kp) for the motors.
This method updates the proportional gain values for the specified motors by writing to their control table.
- Parameters:
kp (List[float]) – A list of proportional gain values to be set for the motors.
- set_kp_kd(kp: float, kd: float)¶
Set the proportional (kp) and derivative (kd) gains for the motor.
This function updates the motor’s control parameters by writing the specified proportional and derivative gains to the motor’s registers. The operation is thread-safe.
- Parameters:
kp (float) – The proportional gain to be set for the motor.
kd (float) – The derivative gain to be set for the motor.
- set_parameters(kp=None, kd=None, ki=None, kff1=None, kff2=None, ids=None)¶
Sets the motor control parameters for specified Dynamixel motors.
This function updates the proportional (kp), derivative (kd), integral (ki), and feedforward (kff1, kff2) gains for the motors identified by the given IDs.
- Parameters:
kp (int, optional) – Proportional gain. If None, the parameter is not updated.
kd (int, optional) – Derivative gain. If None, the parameter is not updated.
ki (int, optional) – Integral gain. If None, the parameter is not updated.
kff1 (int, optional) – First feedforward gain. If None, the parameter is not updated.
kff2 (int, optional) – Second feedforward gain. If None, the parameter is not updated.
ids (list of int, optional) – List of motor IDs to update. If None, no motors are updated.
- set_pos(pos: List[float])¶
Sets the position of the motors by updating the desired position.
- Parameters:
pos (List[float]) – A list of position values to set for the motors.
- update_init_pos()¶
Update the initial position to account for any changes in position.
This method reads the current position from the client and calculates the difference from the stored initial position. It then adjusts the initial position to reflect any changes, ensuring that the position remains within the range of [-π, π].
- toddlerbot.actuation.dynamixel_control.get_env_path()¶
Determines the path of the current Python environment.
- Returns:
The path to the current Python environment. If a virtual environment is active, returns the virtual environment’s path. If a conda environment is active, returns the conda environment’s path. Otherwise, returns the system environment’s path.
- Return type:
str
- toddlerbot.actuation.dynamixel_control.set_latency_timer(latency_value: int = 1)¶
Sets the LATENCY_TIMER variable in the port_handler.py file to the specified value.
This function locates the port_handler.py file within the dynamixel_sdk package and updates the LATENCY_TIMER variable to the given latency_value. If the file or the variable is not found, an error message is printed.
- Parameters:
latency_value (int) – The value to set for LATENCY_TIMER. Defaults to 1.