log¶
Utilities for extracting structured information from log data, from reconstructing the robot to reading telemetry variables.
- jiminy_py.log.extract_variables_from_log(log_vars: Dict[str, ndarray], fieldnames: Dict[str, FieldNested] | Sequence[FieldNested] | str, namespace: str = '', *, as_dict: Literal[False] = False) List[ndarray] [source]¶
- jiminy_py.log.extract_variables_from_log(log_vars: Dict[str, ndarray], fieldnames: Dict[str, FieldNested] | Sequence[FieldNested] | str, namespace: str = '', *, as_dict: Literal[True]) Dict[str, ndarray]
Extract values associated with a set of variables in a specific namespace.
- Parameters:
log_vars – Logged variables as a dictionary.
fieldnames – Structured fieldnames.
namespace – Namespace of the fieldnames. Empty string to disable. Optional: Empty by default.
as_dict – Whether to return a dictionary mapping flattened fieldnames to values. Optional: True by default.
- jiminy_py.log.build_robot_from_log(log_data, mesh_path_dir=None, mesh_package_dirs=(), *, robot_name=None)[source]¶
Create and initialize a robot from single- or multi- robot simulations.
Note
It returns a valid and fully initialized robot, that can be used to perform new simulation if added to a Jiminy Engine, but the original controller is lost.
Note
Model options and robot.pinocchio_model will be the same as during the simulation until the next call to reset or set_options methods.
Note
In case of multi-robot simulation, one may use build_robots_from_log for building all robots at once without having the specify explicitly the name for each of them.
- Parameters:
log_data (Dict[str, Any]) – Logged data (constants plus variables) as a dictionary.
mesh_path_dir (str | None) – Overwrite the common root of all absolute mesh paths. It may be necessary to read logs generated on different environments.
mesh_package_dirs (Sequence[str]) – Prepend custom mesh package search path directories to the ones provided by log file. It may be necessary to specify it to read log generated on a different environment.
robot_name (str | None) – Name of the robot to build from log. If None, then the name will be detected automatically in case of single-robot simulations, otherwise it will raise an exception.
- Returns:
Reconstructed robot.
- Return type:
- jiminy_py.log.build_robots_from_log(log_data, mesh_path_dir=None, mesh_package_dirs=())[source]¶
Build all the robots in the log of the simulation.
Note
Internally, this function calls build_robot_from_log to build each available robot. Refer to build_robot_from_log for more information.
- Parameters:
log_data (Dict[str, Any]) – Logged data (constants and variables) as a dictionary.
mesh_path_dir (str | None) – Overwrite the common root of all absolute mesh paths. It which may be necessary to read log generated on a different environment.
mesh_package_dirs (Sequence[str]) – Prepend custom mesh package search path directories to the ones provided by log file. It may be necessary to specify it to read log generated on a different environment.
- Returns:
Sequence of reconstructed robots.
- Return type:
- jiminy_py.log.extract_trajectory_from_log(log_data, robot=None, *, robot_name=None)[source]¶
Extract the minimal required information from raw log data in order to replay the simulation in a viewer.
Note
- It extracts the required data for replay, namely temporal evolution of:
robot configuration: to display of the robot on the scene,
robot velocity: to update velocity-dependent markers such as DCM,
external forces: to update force-dependent markers.
- Parameters:
log_data (Dict[str, Any]) – Logged data (constants and variables) as a dictionary.
robot (Robot | None) – Jiminy robot associated with the logged trajectory. Optional: None by default. If None, then it will be reconstructed from ‘log_data’ using build_robot_from_log.
robot_name (str | None) – Name of the robot to be constructed in the log. If it is not known, call build_robot_from_log.
- Returns:
Dictionary whose keys are the name of each robot and values are the corresponding Trajectory object.
- Return type:
- jiminy_py.log.extract_trajectories_from_log(log_data, robots=None)[source]¶
Extract the minimal required information from raw log data in order to replay the simulation in a viewer.
Note
This function calls extract_trajectory_from_log to extract each robot’s trajectory. Refer to extract_trajectory_from_log for more information.
- Parameters:
- Returns:
Dictionary mapping each robot name to its corresponding trajectory.
- Return type:
- jiminy_py.log.update_sensor_measurements_from_log(log_data, robot)[source]¶
Helper to make it easy to emulate sensor data update based on log data.
Note
It returns an update_hook that can forwarding the Viewer.replay to display sensor information such as contact forces for instance.
- Parameters:
- Returns:
Callable taking update time in argument and returning nothing. Note that it does not through an exception if out-of-range, but rather clip to desired time to the available data range.
- Return type: