Skip to content

Commit

Permalink
[core] Remove irrelevant telemetry prefix.
Browse files Browse the repository at this point in the history
  • Loading branch information
Alexis Duburcq committed Apr 12, 2024
1 parent 78712dc commit 5cd242c
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 27 deletions.
2 changes: 1 addition & 1 deletion core/include/jiminy/core/engine/engine.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

namespace jiminy
{
inline constexpr std::string_view ENGINE_TELEMETRY_NAMESPACE{"HighLevelController"};
inline constexpr std::string_view ENGINE_TELEMETRY_NAMESPACE{""};

enum class ContactModelType : uint8_t
{
Expand Down
46 changes: 20 additions & 26 deletions python/jiminy_py/src/jiminy_py/log.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
from .dynamics import State, TrajectoryDataType


ENGINE_NAMESPACE = "HighLevelController"
SENSORS_FIELDS: Dict[
Type[jiminy.AbstractSensor], Union[List[str], Dict[str, List[str]]]
] = {
Expand All @@ -52,33 +51,34 @@
@overload
def extract_variables_from_log(log_vars: Dict[str, np.ndarray],
fieldnames: FieldNested,
namespace: Optional[str] = ENGINE_NAMESPACE, *,
as_dict: Literal[False] = False
namespace: str = "HighLevelController",
*, as_dict: Literal[False] = False
) -> List[np.ndarray]:
...


@overload
def extract_variables_from_log(log_vars: Dict[str, np.ndarray],
fieldnames: FieldNested,
namespace: Optional[str] = ENGINE_NAMESPACE, *,
as_dict: Literal[True]
namespace: str = "HighLevelController",
*, as_dict: Literal[True]
) -> Dict[str, np.ndarray]:
...


def extract_variables_from_log(log_vars: Dict[str, np.ndarray],
fieldnames: FieldNested,
namespace: Optional[str] = ENGINE_NAMESPACE, *,
as_dict: bool = False) -> Union[
namespace: str = "HighLevelController",
*, as_dict: bool = False
) -> Union[
List[np.ndarray], Dict[str, np.ndarray]]:
"""Extract values associated with a set of variables in a specific
namespace.
:param log_vars: Logged variables as a dictionary.
:param fieldnames: Structured fieldnames.
:param namespace: Namespace of the fieldnames. None to disable.
Optional: ENGINE_TELEMETRY_NAMESPACE by default.
:param namespace: Namespace of the fieldnames. Empty string to disable.
Optional: "HighLevelController" by default.
:param keep_structure: Whether to return a dictionary mapping flattened
fieldnames to values.
Optional: True by default.
Expand All @@ -93,9 +93,7 @@ def extract_variables_from_log(log_vars: Dict[str, np.ndarray],
values: List[np.ndarray] = []
for fieldname_path, fieldname in tree.flatten_with_path(fieldnames):
# A key is the concatenation of namespace and full path of fieldname
key = ".".join(map(str, filter(
lambda key: isinstance(key, str),
(namespace, *fieldname_path, fieldname))))
key = ".".join(filter(None, (namespace, *fieldname_path, fieldname)))

# Raise an exception if the key does not exists and not fail safe
if key not in log_vars:
Expand Down Expand Up @@ -151,9 +149,6 @@ def build_robot_from_log(
:returns: Reconstructed robot, and parsed log data as returned by
`jiminy_py.log.read_log` method.
"""
# Prepare robot namespace
robot_namespace = ".".join(filter(None, (ENGINE_NAMESPACE, robot_name)))

# Instantiate empty robot
robot = jiminy.Robot(robot_name)

Expand All @@ -162,7 +157,7 @@ def build_robot_from_log(

try:
pinocchio_model = log_constants[
".".join((robot_namespace, "pinocchio_model"))]
".".join(filter(None, (robot_name, "pinocchio_model")))]
except KeyError as e:
if robot_name == "":
raise ValueError(
Expand All @@ -172,20 +167,20 @@ def build_robot_from_log(
try:
# Extract geometry models
collision_model = log_constants[
".".join((robot_namespace, "collision_model"))]
".".join(filter(None, (robot_name, "collision_model")))]
visual_model = log_constants[
".".join((robot_namespace, "visual_model"))]
".".join(filter(None, (robot_name, "visual_model")))]

# Initialize the model
robot.initialize(pinocchio_model, collision_model, visual_model)
except KeyError as e:
# Extract initialization arguments
urdf_data = log_constants[
".".join((robot_namespace, "urdf_file"))]
".".join(filter(None, (robot_name, "urdf_file")))]
has_freeflyer = int(log_constants[
".".join((robot_namespace, "has_freeflyer"))])
".".join(filter(None, (robot_name, "has_freeflyer")))])
mesh_package_dirs = [*mesh_package_dirs, *log_constants.get(
".".join((robot_namespace, "mesh_package_dirs")), ())]
".".join(filter(None, (robot_name, "mesh_package_dirs"))), ())]

# Make sure urdf data is available
if len(urdf_data) <= 1:
Expand Down Expand Up @@ -213,7 +208,7 @@ def build_robot_from_log(
os.remove(urdf_path)

# Load the options
all_options = log_constants[".".join((ENGINE_NAMESPACE, "options"))]
all_options = log_constants["options"]
robot.set_options(all_options[robot_name or "robot"])

# Update model in-place.
Expand Down Expand Up @@ -310,7 +305,6 @@ def extract_trajectory_from_log(log_data: Dict[str, Any],
elif robot_name is None:
robot_name = ""

robot_namespace = ".".join(filter(None, (ENGINE_NAMESPACE, robot_name)))
# Handling of default argument(s)
if robot is None:
robot = build_robot_from_log(log_data, robot_name=robot_name)
Expand All @@ -320,13 +314,13 @@ def extract_trajectory_from_log(log_data: Dict[str, Any],

# Extract the joint positions, velocities and external forces over time
positions = np.stack([
log_vars.get(".".join((robot_namespace, field)), [])
log_vars.get(".".join(filter(None, (robot_name, field))), [])
for field in robot.log_position_fieldnames], axis=-1)
velocities = np.stack([
log_vars.get(".".join((robot_namespace, field)), [])
log_vars.get(".".join(filter(None, (robot_name, field))), [])
for field in robot.log_velocity_fieldnames], axis=-1)
forces = np.stack([
log_vars.get(".".join((robot_namespace, field)), [])
log_vars.get(".".join(filter(None, (robot_name, field))), [])
for field in robot.log_f_external_fieldnames], axis=-1)

# Determine which optional data are available
Expand Down

0 comments on commit 5cd242c

Please sign in to comment.