simulator

This module implements a basic wrapper on top of the lower-level Jiminy Engine that simplifies the user API for the very common single-robot scenario while extending its capability by integrating native support of 3D scene rendering and figure plotting of telemetry log data.

class jiminy_py.simulator.Simulator(robot, viewer_kwargs=None, **kwargs)[source]

Bases: object

Simulation wrapper providing a unified user-API on top of the low-level jiminy C++ core library and Python-native modules for 3D rendering and log data visualization.

The simulation can now be multi-robot but it has been design to remain as easy of use as possible for single-robot simulation which are just multi-robot simulations with only one robot.

  • Single-robot simulations: The name of the robot is an empty string by

default but can be specified. It will then appear in the log if specified. * Multi-robots simulations: The name of the first robot is an empty string by default but it is advised to specify one. You can add robots to the simulation with the method add_robot, robot names have to be specified.

Some proxy and methods are not compatible with multi-robot simulations:

Single-robot simulations | Multi-robot simulations

Simulator.robot_state —> Simulator.engine.robot_states

Simulator.register_profile_force -> Simulator.engine.register_profile_force Simulator.register_impulse_force -> Simulator.engine.register_impulse_force

The methods replay and plot are not supported for multi-robot simulations at the time being.

In case of multi-robot simulations, single-robot proxies either return information associated with the first robot or raise an exception.

Parameters:
  • robot (Robot) – Jiminy robot already initialized.

  • viewer_kwargs (Dict[str, Any] | None) – Keyword arguments to override default arguments whenever a viewer must be instantiated, eg when render method is first called. Specifically, backend is ignored if one is already available. Optional: None by default.

  • kwargs (Any) – Used arguments to allow automatic pipeline wrapper generation.

classmethod build(urdf_path, hardware_path=None, mesh_path_dir=None, has_freeflyer=True, config_path=None, avoid_instable_collisions=True, debug=False, *, name='', **kwargs)[source]

Create a new single-robot simulator instance from scratch based on configuration files only.

Parameters:
  • urdf_path (str) – Path of the urdf model to be used for the simulation.

  • hardware_path (str | None) – Path of Jiminy hardware description toml file. Optional: Looking for ‘*_hardware.toml’ file in the same folder and with the same name.

  • mesh_path_dir (str | None) – Path to the folder containing all the meshes. Optional: Env variable ‘JIMINY_DATA_PATH’ will be used if available.

  • has_freeflyer (bool) – Whether the robot is fixed-based wrt its root link, or can move freely in the world. Optional: True by default.

  • config_path (str | None) – Configuration toml file to import. It will be imported AFTER loading the hardware description file. It can be automatically generated from an instance by calling export_config_file method. One can specify None for loading for the file having the same full path as the URDF file but suffix ‘_options.toml’ if any. Passing an empty string “” will force skipping import completely. Optional: Empty by default

  • avoid_instable_collisions (bool) – Prevent numerical instabilities by replacing collision mesh by vertices of associated minimal volume bounding box, and replacing primitive box by its vertices.

  • debug (bool) – Whether the debug mode must be activated. Doing it enables temporary files automatic deletion.

  • name (str) – Desired name of the robot. Optional: Empty string by default.

  • kwargs (Any) – Keyword arguments to forward to class constructor.

Return type:

Simulator

add_robot(name, urdf_path, hardware_path=None, mesh_path_dir=None, has_freeflyer=True, avoid_instable_collisions=True, debug=False)[source]

Create a new robot from scratch based on configuration files only and add it to the simulator.

Parameters:
  • urdf_path (str) – Path of the urdf model to be used for the simulation.

  • hardware_path (str | None) – Path of Jiminy hardware description toml file. Optional: Looking for ‘*_hardware.toml’ file in the same folder and with the same name.

  • mesh_path_dir (str | None) – Path to the folder containing all the meshes. Optional: Env variable ‘JIMINY_DATA_PATH’ will be used if available.

  • has_freeflyer (bool) – Whether the robot is fixed-based wrt its root link, or can move freely in the world. Optional: True by default.

  • avoid_instable_collisions (bool) – Prevent numerical instabilities by replacing collision mesh by vertices of associated minimal volume bounding box, and replacing primitive box by its vertices.

  • debug (bool) – Whether the debug mode must be activated. Doing it enables temporary files automatic deletion.

  • name (str)

Return type:

None

property viewer: Viewer | None

Convenience proxy to get the viewer associated with the robot that was first added if any.

property viewers: Sequence[Viewer]

Convenience proxy to get all the viewers associated with the ongoing simulation.

property robot: Robot

Convenience proxy to get the robot in single-robot simulations.

Internally, all it does is returning self.engine.robots[0] without any additional processing.

Warning

Method only supported for single-robot simulations. Call

self.engine.robots in multi-robot simulations.

property robot_state: RobotState

Convenience proxy to get the state of the robot in single-robot simulations.

Internally, all it does is returning self.engine.robot_states[0] without any additional processing.

Warning

Method only supported for single-robot simulations. Call self.engine.robot_states in multi-robot simulations.

property is_viewer_available: bool

Returns whether some viewer instances associated with the ongoing simulation is currently opened.

Warning

Method only supported for single-robot simulations.

register_profile_force(frame_name, force_func, update_period=0.0)[source]

Apply an external force profile on a given frame.

The force can be time- and state-dependent, and may be time-continuous or updated periodically (Zero-Order Hold).

Parameters:
  • frame_name (str) – Name of the frame at which to apply the force.

  • force_func (Callable[[float, ndarray, ndarray, ndarray], None]) – Force profile as a callable with signature:

    force_func(
    t: float,
    q: np.ndarray,
    v: np.ndarray,
    force: np.ndarray
    ) -> None

    where force corresponds the spatial force in local world aligned frame, ie its origin is located at application frame but its basis is aligned with world frame. It is represented as a np.ndarray (Fx, Fy, Fz, Mx, My, Mz) that must be updated in-place.

  • update_period (float) – Update period of the force. It must be set to 0.0 for time-continuous. Discrete update is strongly recommended for native Python callables because evaluating them is so slow that it would slowdown the whole simulation. There is no issue for C++ bindings such as jiminy.RandomPerlinProcess.

Return type:

None

register_impulse_force(frame_name, t, dt, force)[source]

Apply an external impulse force on a given frame.

The force starts at the fixed point in time and lasts a given duration. In the meantime, its profile is square-shaped, ie the force remains constant.

Parameters:
  • frame_name (str) – Name of the frame at which to apply the force.

  • t (float) – Time at which to start applying the external force.

  • dt (float) – Duration of the force.

  • force_func – Spatial force in local world aligned frame, ie its origin is located at application frame but its basis is aligned with world frame. It is represented as a np.ndarray (Fx, Fy, Fz, Mx, My, Mz).

  • force (ndarray)

Return type:

None

seed(seed)[source]

Set the seed of the simulation and reset the simulation.

Warning

It also resets the low-level jiminy Engine. Therefore one must call the reset method manually afterward.

Parameters:

seed (uint32 | ndarray) – Desired seed as a sequence of unsigned integers 32 bits.

Return type:

None

reset(remove_all_forces=False)[source]

Reset the simulator.

It resets the simulation time to zero, and generate a new random model of the robot. If one wants to get exactly the same result as before, either set the randomness of the model and sensors to zero, or set the seed once again to reinitialize the random number generator.

Parameters:

remove_all_forces (bool) – Whether to remove already registered external forces. Note that it can also be done separately by calling remove_all_forces method. Optional: Do not remove by default.

Return type:

None

start(q_init, v_init, a_init=None, is_state_theoretical=None)[source]

Initialize a simulation, starting from (q_init, v_init) at t=0.

Parameters:
  • q_init (ndarray | Dict[str, ndarray]) – Initial configuration (by robot if it is a dictionary).

  • v_init (ndarray | Dict[str, ndarray]) – Initial velocity (by robot if it is a dictionary).

  • a_init (ndarray | Dict[str, ndarray] | None) – Initial acceleration (by robot if it is a dictionary). It is only used by acceleration dependent sensors and controllers, such as IMU and force sensors.

  • is_state_theoretical (bool | None) – Whether the initial state is associated with the actual or theoretical model of the robot. This option is only supported when passing np.ndarray for starting a single-robot simulation.

Return type:

None

simulate(t_end, q_init, v_init, a_init=None, is_state_theoretical=None, callback=None, log_path=None, show_progress_bar=True)[source]

Run a simulation, starting from x0=(q0,v0) at t=0 up to tf.

Note

Optionally, log the result of the simulation.

Parameters:
  • t_end (float) – Simulation duration.

  • q_init (ndarray | Dict[str, ndarray]) – Initial configuration (by robot if it is a dictionnary).

  • v_init (ndarray | Dict[str, ndarray]) – Initial velocity (by robot if it is a dictionnary).

  • a_init (ndarray | Dict[str, ndarray] | None) – Initial acceleration (by robot if it is a dictionnary). It is only used by acceleration dependent sensors and controllers, such as IMU and force sensors.

  • is_state_theoretical (bool | None) – In single robot simulations, whether the initial state is associated with the actual or theoretical model of the robot.

  • callback (Callable[[], bool] | None) – Callable that can be specified to abort simulation. It will be evaluated after every simulation step. Abort if false is returned. Optional: None by default.

  • log_path (str | None) – Save log data to this location. Disable if None. Note that the format extension ‘.data’ is enforced. Optional, disable by default.

  • show_progress_bar (bool) – Whether to display a progress bar during the simulation. None to enable only if available. Optional: None by default.

Return type:

None

render(return_rgb_array=False, width=None, height=None, camera_pose=None, update_ground_profile=None, **kwargs)[source]

Render the current state of the simulation. One can display it or return an RGB array instead.

Parameters:
  • return_rgb_array (bool) – Whether to return the current frame as an rgb array or render it directly.

  • width (int | None) – Width of the returned RGB frame, if enabled.

  • height (int | None) – Height of the returned RGB frame, if enabled.

  • camera_pose (Tuple[Tuple[float, float, float] | ndarray | None, Tuple[float, float, float] | ndarray | None, int | str | None] | None) – Tuple position [X, Y, Z], rotation [Roll, Pitch, Yaw], frame name/index specifying the absolute or relative pose of the camera. None to disable. Optional: None by default.

  • update_ground_profile (bool | None) – Whether to update the ground profile. It must be called manually only if necessary because it is costly. Optional: True by default if no viewer available, False otherwise.

  • kwargs (Any) – Extra keyword arguments to forward at Viewer initialization.

Returns:

Rendering as an RGB array (3D numpy array), if enabled, None otherwise.

Return type:

ndarray | None

replay(extra_logs_files=(), extra_trajectories=(), **kwargs)[source]

Replay the current episode until now.

Warning

Method only supported for single-robot simulations.

Parameters:
  • kwargs (Any) – Extra keyword arguments for delegation to replay.play_trajectories method.

  • extra_logs_files (Sequence[str])

  • extra_trajectories (Sequence[Trajectory])

Return type:

None

close()[source]

Close the connection with the renderer.

Return type:

None

plot(enable_flexiblity_data=False, block=None, **kwargs)[source]

Display common simulation data over time.

The figure features several tabs:

  • Subplots with robot configuration

  • Subplots with robot velocity

  • Subplots with robot acceleration

  • Subplots with motors torques

  • Subplots with raw sensor data (one tab for each type of sensor)

Parameters:
  • enable_flexiblity_data (bool) – Enable display of flexibility joints in robot’s configuration, velocity and acceleration subplots. Optional: False by default.

  • block (bool | None) – Whether to wait for the figure to be closed before returning. Optional: False in interactive mode, True otherwise.

  • kwargs (Any) – Extra keyword arguments to forward to TabbedFigure.

Return type:

TabbedFigure | Sequence[TabbedFigure]

export_options(config_path)[source]

Export in a single configuration file all the options of the simulator, ie the engine and all the robots.

Note

The generated configuration file can be imported thereafter using import_options method.

Parameters:

config_path (str | PathLike) – Full path of the location where to store the generated file. The extension ‘.toml’ will be enforced.

Return type:

None

import_options(config_path)[source]

Import all the options of the simulator at once, ie the engine and all the robots.

Note

A full configuration file can be exported beforehand using export_options method.

Parameters:

config_path (str | PathLike) – Full path of the configuration file to load.

Return type:

None