toddlerbot.sim package¶
Submodules¶
toddlerbot.sim.mujoco_control module¶
toddlerbot.sim.mujoco_sim module¶
toddlerbot.sim.mujoco_utils module¶
toddlerbot.sim.real_world module¶
- class toddlerbot.sim.real_world.RealWorld(robot: Robot)¶
Bases:
BaseSim
Real-world robot interface class.
- close()¶
Closes all active components and shuts down the executor.
This method checks for active components such as Dynamixel motors and IMU sensors. If they are present, it submits tasks to close them using the executor. Finally, it shuts down the executor, ensuring all submitted tasks are completed before termination.
- get_observation(retries: int = 0)¶
Retrieve and process sensor observations asynchronously.
This method collects data from available sensors, such as Dynamixel motors and IMU, using asynchronous calls. It processes the collected data to generate a comprehensive observation object.
- Parameters:
retries (int, optional) – The number of retry attempts for obtaining motor state data. Defaults to 0.
- Returns:
An observation object containing processed sensor data, including motor states and, if available, IMU angular velocity and Euler angles.
- initialize() None ¶
Initializes the robot’s components, including IMU and Dynamixel controllers, if available.
This method sets up a thread pool executor to initialize the IMU and Dynamixel controllers asynchronously. It checks the operating system type to determine the appropriate port description for Dynamixel communication. If the robot is configured with an IMU, it initializes the IMU in a separate thread. Similarly, if the robot has Dynamixel actuators, it configures and initializes the Dynamixel controller using the specified port, baud rate, and control parameters. After initialization, it retrieves the results of the asynchronous operations and assigns them to the respective attributes. Finally, it performs a series of observations to ensure the components are functioning correctly.
- process_motor_reading(results: Dict[str, Dict[int, JointState]]) Obs ¶
Processes motor readings and returns an observation object.
- Parameters:
results (Dict[str, Dict[int, JointState]]) – A dictionary containing motor state data, indexed by motor type and ID.
- Returns:
An observation object containing the current time, motor positions, velocities, and torques.
- Return type:
- set_motor_kps(motor_kps: Dict[str, float])¶
Sets the proportional gain (Kp) values for motors of type ‘dynamixel’.
If the robot has Dynamixel motors, this method updates their Kp values based on the provided dictionary. If a motor’s Kp is not specified in the dictionary, it defaults to the value in the robot’s configuration.
- Parameters:
motor_kps (Dict[str, float]) – A dictionary mapping motor names to their desired Kp values.
- set_motor_target(motor_angles: Dict[str, float])¶
Sets the target angles for the robot’s motors, adjusting for any negated motor directions and updating the positions of Dynamixel motors if present.
- Parameters:
motor_angles (Dict[str, float]) – A dictionary mapping motor names to their target angles in degrees.
- step()¶
toddlerbot.sim.robot module¶
- class toddlerbot.sim.robot.Robot(robot_name: str)¶
Bases:
object
This class defines some data strucutres, FK, IK of ToddlerBot.
- get_joint_attrs(key_name: str, key_value: Any, attr_name: str = 'name', group: str = 'all') List[Any] ¶
Returns a list of attributes for joints that match specified criteria.
- Parameters:
key_name (str) – The key to search for in each joint’s configuration.
key_value (Any) – The value that the specified key must have for a joint to be included.
attr_name (str, optional) – The attribute to retrieve from each matching joint. Defaults to “name”.
group (str, optional) – The group to which the joint must belong. Use “all” to include joints from any group. Defaults to “all”.
- Returns:
A list of attributes from joints that match the specified key-value pair and group criteria.
- Return type:
List[Any]
- initialize() None ¶
Initializes the robot’s joint and motor configurations based on the provided configuration data.
This method sets up the initial and default motor angles, establishes mappings between motors and joints, identifies passive joints, and configures collision detection. It also determines the presence of a gripper and sets joint groups and limits.
- init_motor_angles¶
Initial motor angles for active joints.
- Type:
Dict[str, float]
- init_joint_angles¶
Initial joint angles derived from motor angles.
- Type:
Dict[str, float]
- motor_ordering¶
Order of motors based on initial configuration.
- Type:
List[str]
- joint_ordering¶
Order of joints based on initial configuration.
- Type:
List[str]
- default_motor_angles¶
Default motor angles for active joints.
- Type:
Dict[str, float]
- default_joint_angles¶
Default joint angles derived from motor angles.
- Type:
Dict[str, float]
- motor_to_joint_name¶
Mapping from motor names to joint names.
- Type:
Dict[str, List[str]]
- joint_to_motor_name¶
Mapping from joint names to motor names.
- Type:
Dict[str, List[str]]
- passive_joint_names¶
Names of passive joints.
- Type:
List[str]
- foot_name¶
Name of the foot, if specified in the configuration.
- Type:
str
- has_gripper¶
Indicates if the robot has a gripper.
- Type:
bool
- collider_names¶
Names of links with collision enabled.
- Type:
List[str]
- nu¶
Number of active motors.
- Type:
int
- joint_groups¶
Group classification for each joint.
- Type:
Dict[str, str]
- joint_limits¶
Lower and upper limits for each joint.
- Type:
Dict[str, List[float]]
- joint_to_motor_angles(joint_angles: Dict[str, float]) Dict[str, float] ¶
Converts joint angles to motor angles based on the transmission type specified in the configuration.
- Parameters:
joint_angles (Dict[str, float]) – A dictionary mapping joint names to their respective angles.
- Returns:
A dictionary mapping motor names to their calculated angles.
- Return type:
Dict[str, float]
- joint_to_passive_angles(joint_angles: Dict[str, float]) Dict[str, float] ¶
Converts joint angles to passive angles based on the transmission type.
This function processes a dictionary of joint angles and converts them into passive angles using the transmission configuration specified in the object’s configuration. It supports two types of transmissions: ‘linkage’ and ‘rack_and_pinion’. For ‘linkage’ transmissions, it generates additional passive angles with specific suffixes, applying a sign change for knee joints. For ‘rack_and_pinion’ transmissions, it mirrors the joint angle.
- Parameters:
joint_angles (Dict[str, float]) – A dictionary where keys are joint names and values are their respective angles.
- Returns:
A dictionary of passive angles derived from the input joint angles.
- Return type:
Dict[str, float]
- load_robot_config()¶
Load the robot’s configuration and collision configuration from JSON files.
- Raises:
FileNotFoundError – If the main configuration file or the collision configuration file does not exist at the specified paths.
- motor_to_joint_angles(motor_angles: Dict[str, float]) Dict[str, float] ¶
Converts motor angles to joint angles based on the robot’s configuration.
- Parameters:
motor_angles (Dict[str, float]) – A dictionary mapping motor names to their respective angles.
- Returns:
A dictionary mapping joint names to their calculated angles.
- Return type:
Dict[str, float]
- set_joint_attrs(key_name: str, key_value: Any, attr_name: str, attr_values: Any, group: str = 'all')¶
Sets attributes for joints in the configuration based on specified criteria.
- Parameters:
key_name (str) – The key to match in each joint’s configuration.
key_value (Any) – The value that the key must have for the joint to be modified.
attr_name (str) – The name of the attribute to set for matching joints.
attr_values (Any) – The values to assign to the attribute. Can be a dictionary or a list.
group (str, optional) – The group to which the joint must belong to be modified. Defaults to “all”.
- waist_fk(motor_pos: List[float]) List[float] ¶
Calculates the forward kinematics for the waist joint based on motor positions.
- Parameters:
motor_pos (List[float]) – A list containing the positions of the motors.
- Returns:
A list containing the calculated waist roll and yaw angles.
- Return type:
List[float]
- waist_ik(waist_pos: List[float]) List[float] ¶
Calculates the inverse kinematics for the waist actuators based on the desired waist position.
- Parameters:
waist_pos (List[float]) – A list containing the desired roll and yaw positions of the waist.
- Returns:
A list containing the calculated positions for the two waist actuators.
- Return type:
List[float]
Module contents¶
- class toddlerbot.sim.BaseSim(name: str)¶
Bases:
ABC
Base class for simulation environments
- abstract close()¶
- abstract set_motor_kps(motor_kps: Dict[str, float])¶
- abstract set_motor_target(motor_angles: Dict[str, float])¶
- abstract step()¶
- class toddlerbot.sim.Obs(time: float, motor_pos: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]], motor_vel: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]], motor_tor: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]], lin_vel: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] = <factory>, ang_vel: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] = <factory>, pos: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] = <factory>, euler: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] = <factory>, joint_pos: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] | None = None, joint_vel: ~numpy.ndarray[~typing.Any, ~numpy.dtype[~numpy.float32]] | None = None)¶
Bases:
object
Observation data structure
- ang_vel: ndarray[Any, dtype[float32]]¶
- euler: ndarray[Any, dtype[float32]]¶
- joint_pos: ndarray[Any, dtype[float32]] | None = None¶
- joint_vel: ndarray[Any, dtype[float32]] | None = None¶
- lin_vel: ndarray[Any, dtype[float32]]¶
- motor_pos: ndarray[Any, dtype[float32]]¶
- motor_tor: ndarray[Any, dtype[float32]]¶
- motor_vel: ndarray[Any, dtype[float32]]¶
- pos: ndarray[Any, dtype[float32]]¶
- time: float¶