toddlerbot.reference package

Submodules

toddlerbot.reference.cartwheel_ref module

Cartwheel motion reference implementation for toddlerbot.

Provides cartwheel motion references using precomputed motion data.

class toddlerbot.reference.cartwheel_ref.CartwheelReference(robot, dt: float, fixed_base: bool = False)

Bases: MotionReference

Motion reference for cartwheel movements using precomputed motion data.

get_phase_signal(time_curr: float, init_idx: int = 0) Array | ndarray[Any, dtype[float32]]

Get the phase signal for the current time.

get_state_ref(time_curr: float, command: Array | ndarray[Any, dtype[float32]], last_state: Dict[str, Array | ndarray[Any, dtype[float32]]], init_idx: int = 0) Dict[str, Array | ndarray[Any, dtype[float32]]]

Get the reference state for the current time. Supports RIS if fed init_idx

Parameters:
  • time_curr (float) – The current time.

  • command (ArrayType) – Command inputs for the robot’s movement.

  • last_state (Dict[str, ArrayType]) – The last state of the robot.

  • init_idx (int, optional) – Starting initial state index for RIS. Defaults to 0.

Returns:

A dictionary containing the path state, motor positions, joint positions, body poses, and other reference data.

Return type:

Dict[str, ArrayType]

get_vel(command: Array | ndarray[Any, dtype[float32]]) Tuple[Array | ndarray[Any, dtype[float32]], Array | ndarray[Any, dtype[float32]]]

Get the desired linear and angular velocities.

toddlerbot.reference.crawl_ref module

Crawling motion reference implementation for toddlerbot.

Provides crawling motion references using keyframe-based motion data.

class toddlerbot.reference.crawl_ref.CrawlReference(robot, dt: float, fixed_base: bool = False)

Bases: MotionReference

Motion reference for crawling movements using keyframe data.

get_phase_signal(time_curr: float, init_idx: int = 0) Array | ndarray[Any, dtype[float32]]

Get the phase signal for the current time.

get_state_ref(time_curr: float, command: Array | ndarray[Any, dtype[float32]], last_state: Dict[str, Array | ndarray[Any, dtype[float32]]], init_idx: int = 0) Dict[str, Array | ndarray[Any, dtype[float32]]]

Get the reference state for the current time. Supports RIS if fed init_idx

Parameters:
  • time_curr (float) – The current time.

  • command (ArrayType) – Command inputs for the robot’s movement.

  • last_state (Dict[str, ArrayType]) – The last state of the robot.

  • init_idx (int, optional) – Starting initial state index for RIS. Defaults to 0.

Returns:

A dictionary containing the path state, motor positions, joint positions, body poses, and other reference data.

Return type:

Dict[str, ArrayType]

get_vel(command: Array | ndarray[Any, dtype[float32]]) Tuple[Array | ndarray[Any, dtype[float32]], Array | ndarray[Any, dtype[float32]]]

Get the desired linear and angular velocities.

toddlerbot.reference.motion_ref module

Abstract base class for motion references in toddlerbot.

Defines the interface for generating motion references and provides common functionality for robot motion control including path integration and state management.

class toddlerbot.reference.motion_ref.Motion(time: Array | ndarray[Any, dtype[float32]], qpos: Array | ndarray[Any, dtype[float32]], body_pos: Array | ndarray[Any, dtype[float32]], body_quat: Array | ndarray[Any, dtype[float32]], site_pos: Array | ndarray[Any, dtype[float32]], site_quat: Array | ndarray[Any, dtype[float32]], action: Array | ndarray[Any, dtype[float32]] | None = None, contact: Array | ndarray[Any, dtype[float32]] | None = None)

Bases: object

Data structure for storing motion reference data.

action: Array | ndarray[Any, dtype[float32]] | None = None
body_pos: Array | ndarray[Any, dtype[float32]]
body_quat: Array | ndarray[Any, dtype[float32]]
contact: Array | ndarray[Any, dtype[float32]] | None = None
qpos: Array | ndarray[Any, dtype[float32]]
site_pos: Array | ndarray[Any, dtype[float32]]
site_quat: Array | ndarray[Any, dtype[float32]]
time: Array | ndarray[Any, dtype[float32]]
class toddlerbot.reference.motion_ref.MotionReference(name: str, motion_type: str, robot: Robot, dt: float, fixed_base: bool = False)

Bases: ABC

Abstract class for generating motion references for the toddlerbot robot.

get_default_state() Dict[str, Array | ndarray[Any, dtype[float32]]]

Returns the default state of the robot, including position, orientation, and velocities.

This method initializes the robot’s state with default values for position, orientation (as a quaternion), linear velocity, angular velocity, motor positions, joint positions, and stance mask.

Returns:

A dictionary containing the default state of the robot.

Return type:

Dict[str, ArrayType]

get_phase_signal(time_curr: float | Array | ndarray[Any, dtype[float32]]) Array | ndarray[Any, dtype[float32]]

Calculate the phase signal at a given time.

Parameters:

time_curr (float | ArrayType) – The current time or an array of time values.

Returns:

An array containing the phase signal, initialized to zeros.

Return type:

ArrayType

abstractmethod get_state_ref(time_curr: float | Array | ndarray[Any, dtype[float32]], command: Array | ndarray[Any, dtype[float32]], last_state: Dict[str, Array | ndarray[Any, dtype[float32]]], init_idx: int = 0) Dict[str, Array | ndarray[Any, dtype[float32]]]
abstractmethod get_vel(command: Array | ndarray[Any, dtype[float32]]) Tuple[Array | ndarray[Any, dtype[float32]], Array | ndarray[Any, dtype[float32]]]
integrate_path_state(command: Array | ndarray[Any, dtype[float32]], last_state: Dict[str, Array | ndarray[Any, dtype[float32]]]) Dict[str, Array | ndarray[Any, dtype[float32]]]

Integrates the current state of a path with a given command to compute the next state.

This function calculates the new position and orientation of an object by integrating its current state with a command that specifies linear and angular velocities. The orientation is updated using quaternion multiplication to apply roll, pitch, and yaw rotations.

Parameters:
  • last_state (ArrayType) – The current state of the object, including position, orientation (as a quaternion), linear velocity, and angular velocity.

  • command (ArrayType) – The command input specifying desired linear and angular velocities.

Returns:

The updated state of the object, including new position, orientation, linear velocity, and angular velocity.

Return type:

ArrayType

toddlerbot.reference.walk_zmp_ref module

ZMP-based walking motion reference implementation for toddlerbot.

Provides walking motion references using Zero Moment Point (ZMP) control with lookup tables.

class toddlerbot.reference.walk_zmp_ref.WalkZMPReference(robot: Robot, dt: float, cycle_time: float, fixed_base: bool = False)

Bases: MotionReference

Class for generating a ZMP-based walking reference for the toddlerbot robot.

get_phase_signal(time_curr: float | Array | ndarray[Any, dtype[float32]]) Array | ndarray[Any, dtype[float32]]

Calculate the phase signal as a sine and cosine pair for a given time.

Parameters:

time_curr (float | ArrayType) – The current time or an array of time values.

Returns:

A numpy array containing the sine and cosine of the phase, with dtype float32.

Return type:

ArrayType

get_state_ref(time_curr: float | Array | ndarray[Any, dtype[float32]], command: Array | ndarray[Any, dtype[float32]], last_state: Dict[str, Array | ndarray[Any, dtype[float32]]], init_idx: int = 0, torso_yaw: float = 0.0) Dict[str, Array | ndarray[Any, dtype[float32]]]

Generate a reference state for a robotic system based on the current state, time, and command inputs.

This function calculates the desired joint and motor positions for a robot by integrating the current state with the given command inputs. It interpolates neck, waist, and arm positions, and determines leg joint positions based on whether the robot is in a static pose or dynamic motion. The function returns a concatenated array representing the path state, motor positions, joint positions, and stance mask.

Parameters:
  • time_curr (float | ArrayType) – The current time or time array.

  • command (ArrayType) – Command inputs for the robot’s movement.

  • last_state (ArrayType) – The current state of the robot.

Returns:

A dictionary containing the path state, motor positions, joint positions, and stance mask.

Return type:

Dict[str, ArrayType]

get_vel(command: Array | ndarray[Any, dtype[float32]]) Tuple[Array | ndarray[Any, dtype[float32]], Array | ndarray[Any, dtype[float32]]]

Calculates linear and angular velocities based on the given command array.

The function interprets the command array to extract linear and angular velocity components. The linear velocity is derived from specific indices of the command array, while the angular velocity is determined from another index.

Parameters:

command (ArrayType) – An array containing control commands, where indices 5 and 6 are used for linear velocity components and index 7 for angular velocity.

Returns:

A tuple containing the linear velocity as the first element and the angular velocity as the second element, both as numpy arrays.

Return type:

Tuple[ArrayType, ArrayType]

Module contents

Reference motion generation and trajectory planning for ToddlerBot.

This package provides reference motion generators and trajectory planning utilities for various robot behaviors and movements, including:

  • ZMP-based walking reference trajectories

  • Cartwheel and acrobatic motion references

  • Crawling and low-profile movement references

  • General motion reference framework and base classes

  • Trajectory interpolation and smoothing utilities

The reference motion system provides target trajectories for various controllers and policies, supporting both scripted motions and dynamically generated reference patterns based on user commands and environmental conditions.