Unverified Commit fd72e345 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Cleanups to the actuator model module (#101)

# Description

This MR adds some missing documentation to the actuator module. It also
splits the `actuator.py` file into `actuator_base.py` and
`actuator_pd.py` files to make it clear where the base class exists.

## Type of change

- Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
parent bd87f9c1
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.8.2"
version = "0.8.3"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.8.3 (2023-08-02)
~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Moved the :class:`ActuatorBase` class to the :mod:`omni.isaac.orbit.actuators.actuator_base` module.
* Renamed the :mod:`omni.isaac.orbit.actuators.actuator` module to :mod:`omni.isaac.orbit.actuators.actuator_pd`
to make it more explicit that it contains the PD actuator models.
0.8.2 (2023-08-02)
~~~~~~~~~~~~~~~~~~
......
......@@ -5,6 +5,35 @@
"""Subpackage for handling actuator models."""
from .actuator import ActuatorBase, DCMotor, IdealPDActuator, ImplicitActuator
from .actuator_cfg import ActuatorBaseCfg, ActuatorNetLSTMCfg, ActuatorNetMLPCfg, DCMotorCfg, IdealPDActuatorCfg
from .actuator_base import ActuatorBase
from .actuator_cfg import (
ActuatorBaseCfg,
ActuatorNetLSTMCfg,
ActuatorNetMLPCfg,
DCMotorCfg,
IdealPDActuatorCfg,
ImplicitActuatorCfg,
)
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
from .actuator_pd import DCMotor, IdealPDActuator, ImplicitActuator
__all__ = [
# base actuator
"ActuatorBase",
"ActuatorBaseCfg",
# implicit actuator
"ImplicitActuatorCfg",
"ImplicitActuator",
# ideal pd actuator
"IdealPDActuatorCfg",
"IdealPDActuator",
# dc motor
"DCMotorCfg",
"DCMotor",
# actuator net -- lstm
"ActuatorNetLSTMCfg",
"ActuatorNetLSTM",
# actuator net -- mlp
"ActuatorNetMLPCfg",
"ActuatorNetMLP",
]
......@@ -10,8 +10,8 @@ from typing import Iterable
from omni.isaac.orbit.utils import configclass
from .actuator import ActuatorBase, DCMotor, IdealPDActuator, ImplicitActuator
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
from . import actuator_net, actuator_pd
from .actuator_base import ActuatorBase
@configclass
......@@ -21,56 +21,71 @@ class ActuatorBaseCfg:
cls: type[ActuatorBase] = MISSING
"""Actuator class."""
dof_name_expr: list[str] = MISSING
"""Articulation's DOF names that are part of the group. Can be regex expressions (e.g. ".*")."""
dof_names_expr: list[str] = MISSING
"""Articulation's joint names that are part of the group.
effort_limit: float | None = None
Note:
This can be a list of joint names or a list of regex expressions (e.g. ".*").
"""
Force/Torque limit of the DOFs in the group. Defaults to :obj:`None`.
effort_limit: float | None = None
"""Force/Torque limit of the joints in the group. Defaults to :obj:`None`.
If :obj:`None`, the limit is set to infinity.
"""
velocity_limit: float | None = None
"""
Velocity limit of the DOFs in the group. Defaults to :obj:`None`.
"""
"""Velocity limit of the joints in the group. Defaults to :obj:`None`.
stiffness: dict[str, float] | None = None
"""
Stiffness gains (Also known as P gain) of the DOFs in the group. Defaults to :obj:`None`.
If :obj:`None`, these are loaded from the articulation prim.
If :obj:`None`, the limit is set to infinity.
"""
damping: dict[str, float] | None = None
stiffness: dict[str, float] | None = MISSING
"""Stiffness gains (also known as p-gain) of the joints in the group.
If :obj:`None`, the stiffness is set to 0.
"""
Damping gains (Also known as D gain) of the DOFs in the group. Defaults to :obj:`None`.
If :obj:`None`, these are loaded from the articulation prim.
damping: dict[str, float] | None = MISSING
"""Damping gains (also known as d-gain) of the joints in the group.
If :obj:`None`, the damping is set to 0.
"""
"""
Implicit Actuator Models.
"""
@configclass
class IdealPDActuatorCfg(ActuatorBaseCfg):
class ImplicitActuatorCfg(ActuatorBaseCfg):
"""Configuration for an ideal PD actuator.
The PD control is handled implicitly by the simulation."""
cls: type[ActuatorBase] = IdealPDActuator
"""Actuator class."""
Note:
The PD control is handled implicitly by the simulation.
"""
cls = actuator_pd.ImplicitActuator
"""
Explicit Actuator Models.
"""
@configclass
class ImplicitPDActuatorCfg(ActuatorBaseCfg):
"""Configuration for an ideal PD actuator.
The PD control is handled implicitly by the simulation."""
class IdealPDActuatorCfg(ActuatorBaseCfg):
"""Configuration for an ideal PD actuator."""
cls: type[ActuatorBase] = ImplicitActuator
"""Actuator class."""
cls = actuator_pd.IdealPDActuator
@configclass
class DCMotorCfg(IdealPDActuatorCfg):
"""Configuration for direct control (DC) motor actuator model."""
cls: type[ActuatorBase] = DCMotor
"""Actuator class."""
cls = actuator_pd.DCMotor
saturation_effort: float = MISSING
"""Peak motor force/torque of the electric DC motor (in N-m)."""
......@@ -80,7 +95,10 @@ class DCMotorCfg(IdealPDActuatorCfg):
class ActuatorNetLSTMCfg(DCMotorCfg):
"""Configuration for LSTM-based actuator model."""
cls: type[ActuatorBase] = ActuatorNetLSTM
cls = actuator_net.ActuatorNetLSTM
# we don't use stiffness and damping for actuator net
stiffness = None
damping = None
network_file: str = MISSING
"""Path to the file containing network weights."""
......@@ -90,7 +108,10 @@ class ActuatorNetLSTMCfg(DCMotorCfg):
class ActuatorNetMLPCfg(DCMotorCfg):
"""Configuration for MLP-based actuator model."""
cls: type[ActuatorBase] = ActuatorNetMLP
cls = actuator_net.ActuatorNetMLP
# we don't use stiffness and damping for actuator net
stiffness = None
damping = None
network_file: str = MISSING
"""Path to the file containing network weights."""
......
......@@ -21,10 +21,10 @@ from omni.isaac.core.utils.types import ArticulationActions
from omni.isaac.orbit.utils.assets import read_file
from .actuator import DCMotor
from .actuator_pd import DCMotor
if TYPE_CHECKING:
from .actuator_cfg import ActuatorBaseCfg, ActuatorNetLSTMCfg, ActuatorNetMLPCfg
from .actuator_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg
class ActuatorNetLSTM(DCMotor):
......@@ -36,45 +36,35 @@ class ActuatorNetLSTM(DCMotor):
hidden states of the recurrent network captures the history.
Note:
The class only supports desired joint positions commands as inputs in the method:
:meth:`ActuatorNetLSTM.set_command`.
Only the desired joint positions are used as inputs to the network.
"""
cfg: ActuatorNetLSTMCfg
"""The configuration of the actuator model."""
def __init__(self, cfg: ActuatorBaseCfg, dof_names: list[str], dof_ids: list[int], num_envs: int, device: str):
def __init__(self, cfg: ActuatorNetLSTMCfg, dof_names: list[str], dof_ids: list[int], num_envs: int, device: str):
super().__init__(cfg, dof_names, dof_ids, num_envs, device)
"""Initializes the actuator net model.
Args:
cfg (ActuatorNetLSTMCfg): The configuration for the actuator model.
num_actuators (int): The number of actuators using the model.
num_envs (int): The number of instances of the articulation.
device (str): The computation device.
"""
# load the model from JIT file
file_bytes = read_file(self.cfg.network_file)
self.network = torch.jit.load(file_bytes, map_location=self.device)
self.network = torch.jit.load(file_bytes, map_location=self._device)
# extract number of lstm layers and hidden dim from the shape of weights
num_layers = len(self.network.lstm.state_dict()) // 4
hidden_dim = self.network.lstm.state_dict()["weight_hh_l0"].shape[1]
# create buffers for storing LSTM inputs
self.sea_input = torch.zeros(self.num_envs * self.num_actuators, 1, 2, device=self.device)
self.sea_input = torch.zeros(self._num_envs * self.num_joints, 1, 2, device=self._device)
self.sea_hidden_state = torch.zeros(
num_layers, self.num_envs * self.num_actuators, hidden_dim, device=self.device
)
self.sea_cell_state = torch.zeros(
num_layers, self.num_envs * self.num_actuators, hidden_dim, device=self.device
num_layers, self._num_envs * self.num_joints, hidden_dim, device=self._device
)
self.sea_cell_state = torch.zeros(num_layers, self._num_envs * self.num_joints, hidden_dim, device=self._device)
# reshape via views (doesn't change the actual memory layout)
layer_shape_per_env = (num_layers, self.num_envs, self.num_actuators, hidden_dim)
layer_shape_per_env = (num_layers, self._num_envs, self.num_joints, hidden_dim)
self.sea_hidden_state_per_env = self.sea_hidden_state.view(layer_shape_per_env)
self.sea_cell_state_per_env = self.sea_cell_state.view(layer_shape_per_env)
def reset(self, env_ids: Sequence[int]):
# reset the hidden and cell states for the specified environments
with torch.no_grad():
self.sea_hidden_state_per_env[:, env_ids] = 0.0
self.sea_cell_state_per_env[:, env_ids] = 0.0
......@@ -85,14 +75,17 @@ class ActuatorNetLSTM(DCMotor):
# compute network inputs
self.sea_input[:, 0, 0] = (control_action.joint_positions - dof_pos).flatten()
self.sea_input[:, 0, 1] = dof_vel.flatten()
# run network inference
with torch.inference_mode():
torques, (self.sea_hidden_state[:], self.sea_cell_state[:]) = self.network(
self.sea_input, (self.sea_hidden_state, self.sea_cell_state)
)
self.computed_effort = torques.reshape(self.num_envs, self.num_actuators)
self.computed_effort = torques.reshape(self._num_envs, self.num_joints)
# clip the computed effort based on the motor limits
self.applied_effort = self._clip_effort(self.computed_effort)
# return torques
control_action.joint_efforts = self.applied_effort
control_action.joint_positions = None
......@@ -115,8 +108,7 @@ class ActuatorNetMLP(DCMotor):
as a TorchScript.
Note:
The class only supports desired joint positions commands as inputs in the method:
:meth:`ActuatorNetMLP.set_command`.
Only the desired joint positions are used as inputs to the network.
"""
......@@ -124,27 +116,19 @@ class ActuatorNetMLP(DCMotor):
"""The configuration of the actuator model."""
def __init__(self, cfg: ActuatorNetMLPCfg, dof_names: list[str], dof_ids: list[int], num_envs: int, device: str):
"""Initializes the actuator net model.
Args:
cfg (ActuatorNetMLPCfg): The configuration for the actuator model.
num_actuators (int): The number of actuators using the model.
num_envs (int): The number of instances of the articulation.
device (str): The computation device.
"""
super().__init__(cfg, dof_names, dof_ids, num_envs, device)
# save config locally
self.cfg = cfg
# load the model from JIT file
file_bytes = read_file(self.cfg.network_file)
self.network = torch.jit.load(file_bytes, map_location=self.device)
self.network = torch.jit.load(file_bytes, map_location=self._device)
# create buffers for MLP history
history_length = max(self.cfg.input_idx) + 1
self._dof_pos_error_history = torch.zeros(self.num_envs, history_length, self.num_actuators, device=self.device)
self._dof_vel_history = torch.zeros(self.num_envs, history_length, self.num_actuators, device=self.device)
self._dof_pos_error_history = torch.zeros(self._num_envs, history_length, self.num_joints, device=self._device)
self._dof_vel_history = torch.zeros(self._num_envs, history_length, self.num_joints, device=self._device)
def reset(self, env_ids: Sequence[int]):
# reset the history for the specified environments
self._dof_pos_error_history[env_ids] = 0.0
self._dof_vel_history[env_ids] = 0.0
......@@ -162,18 +146,20 @@ class ActuatorNetMLP(DCMotor):
# compute network inputs
# -- positions
pos_input = torch.cat([self._dof_pos_error_history[:, i].unsqueeze(2) for i in self.cfg.input_idx], dim=2)
pos_input = pos_input.reshape(self.num_envs * self.num_actuators, -1)
pos_input = pos_input.reshape(self._num_envs * self.num_joints, -1)
# -- velocity
vel_input = torch.cat([self._dof_vel_history[:, i].unsqueeze(2) for i in self.cfg.input_idx], dim=2)
vel_input = vel_input.reshape(self.num_envs * self.num_actuators, -1)
vel_input = vel_input.reshape(self._num_envs * self.num_joints, -1)
# -- scale and concatenate inputs
network_input = torch.cat([vel_input * self.cfg.vel_scale, pos_input * self.cfg.pos_scale], dim=1)
# run network inference
torques = self.network(network_input).reshape(self.num_envs, self.num_actuators)
self.computed_effort = torques.reshape(self.num_envs, self.num_actuators)
torques = self.network(network_input).reshape(self._num_envs, self.num_joints)
self.computed_effort = torques.reshape(self._num_envs, self.num_joints)
# clip the computed effort based on the motor limits
self.applied_effort = self._clip_effort(self.computed_effort)
# return torques
control_action.joint_efforts = self.applied_effort
control_action.joint_positions = None
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import torch
from typing import TYPE_CHECKING, Sequence
from omni.isaac.core.utils.types import ArticulationActions
from .actuator_base import ActuatorBase
if TYPE_CHECKING:
from .actuator_cfg import DCMotorCfg, IdealPDActuatorCfg, ImplicitActuatorCfg
"""
Implicit Actuator Models.
"""
class ImplicitActuator(ActuatorBase):
"""Implicit actuator model that is handled by the simulation.
This performs a similar function as the :class:`IdealPDActuator` class. However, the PD control is handled
implicitly by the simulation which performs continuous-time integration of the PD control law. This is
generally more accurate than the explicit PD control law used in :class:`IdealPDActuator` when the simulation
time-step is large.
.. note::
The articulation class sets the stiffness and damping parameters from the configuration into the simulation.
Thus, the parameters are not used in this class.
.. caution::
The class is only provided for consistency with the other actuator models. It does not implement any
functionality and should not be used. All values should be set to the simulation directly.
"""
cfg: ImplicitActuatorCfg
"""The configuration for the actuator model."""
"""
Operations.
"""
def reset(self, *args, **kwargs):
raise RuntimeError(
"This function should not be called! Implicit actuators are handled directly by the simulation."
)
def compute(self, *args, **kwargs) -> ArticulationActions:
raise RuntimeError(
"This function should not be called! Implicit actuators are handled directly by the simulation."
)
"""
Explicit Actuator Models.
"""
class IdealPDActuator(ActuatorBase):
r"""Ideal torque-controlled actuator model with a simple saturation model.
It employs the following model for computing torques for the actuated joint :math:`j`:
.. math::
\tau_{j, computed} = k_p * (q - q_{des}) + k_d * (\dot{q} - \dot{q}_{des}) + \tau_{ff}
where, :math:`k_p` and :math:`k_d` are joint stiffness and damping gains, :math:`q` and :math:`\dot{q}`
are the current joint positions and velocities, :math:`q_{des}`, :math:`\dot{q}_{des}` and :math:`\tau_{ff}`
are the desired joint positions, velocities and torques commands.
The clipping model is based on the maximum torque applied by the motor. It is implemented as:
.. math::
\tau_{j, max} & = \gamma \times \tau_{motor, max} \\
\tau_{j, applied} & = clip(\tau_{computed}, -\tau_{j, max}, \tau_{j, max})
where the clipping function is defined as :math:`clip(x, x_{min}, x_{max}) = min(max(x, x_{min}), x_{max})`.
The parameters :math:`\gamma` is the gear ratio of the gear box connecting the motor and the actuated joint ends,
and :math:`\tau_{motor, max}` is the maximum motor effort possible. These parameters are read from
the configuration instance passed to the class.
"""
cfg: IdealPDActuatorCfg
"""The configuration for the actuator model."""
"""
Operations.
"""
def reset(self, env_ids: Sequence[int]):
pass
def compute(
self, control_action: ArticulationActions, dof_pos: torch.Tensor, dof_vel: torch.Tensor
) -> ArticulationActions:
# compute errors
error_pos = control_action.joint_positions - dof_pos
error_vel = control_action.joint_velocities - dof_vel
# calculate the desired joint torques
self.computed_effort = self.stiffness * error_pos + self.damping * error_vel + control_action.joint_efforts
# clip the torques based on the motor limits
self.applied_effort = self._clip_effort(self.computed_effort)
# set the computed actions back into the control action
control_action.joint_efforts = self.applied_effort
control_action.joint_positions = None
control_action.joint_velocities = None
return control_action
"""
Helper functions.
"""
def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor:
"""Clip the desired torques based on the motor limits.
Args:
desired_torques (torch.Tensor): The desired torques to clip.
Returns:
torch.Tensor: The clipped torques.
"""
return torch.clip(effort, min=-self.effort_limit, max=self.effort_limit)
class DCMotor(IdealPDActuator):
r"""
Direct control (DC) motor actuator model with velocity-based saturation model.
It uses the same model as the :class:`IdealActuator` for computing the torques from input commands.
However, it implements a saturation model defined by DC motor characteristics.
A DC motor is a type of electric motor that is powered by direct current electricity. In most cases,
the motor is connected to a constant source of voltage supply, and the current is controlled by a rheostat.
Depending on various design factors such as windings and materials, the motor can draw a limited maximum power
from the electronic source, which limits the produced motor torque and speed.
A DC motor characteristics are defined by the following parameters:
* Continuous-rated speed (:math:`\dot{q}_{motor, max}`) : The maximum-rated speed of the motor.
* Continuous-stall torque (:math:`\tau_{motor, max}`): The maximum-rated torque produced at 0 speed.
* Saturation torque (:math:`\tau_{motor, sat}`): The maximum torque that can be outputted for a short period.
Based on these parameters, the instantaneous minimum and maximum torques are defined as follows:
.. math::
\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left(1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), 0.0, \tau_{j, max} \right) \\
\tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left( -1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, max}, 0.0 \right)
where :math:`\gamma` is the gear ratio of the gear box connecting the motor and the actuated joint ends,
:math:`\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}`, :math:`\tau_{j, max} =
\gamma \times \tau_{motor, max}` and :math:`\tau_{j, peak} = \gamma \times \tau_{motor, peak}`
are the maximum joint velocity, maximum joint torque and peak torque, respectively. These parameters
are read from the configuration instance passed to the class.
Using these values, the computed torques are clipped to the minimum and maximum values based on the
instantaneous joint velocity:
.. math::
\tau_{j, applied} = clip(\tau_{computed}, \tau_{j, min}(\dot{q}), \tau_{j, max}(\dot{q}))
"""
cfg: DCMotorCfg
"""The configuration for the actuator model."""
def __init__(self, cfg: DCMotorCfg, dof_names: list[str], dof_ids: list[int], num_envs: int, device: str):
super().__init__(cfg, dof_names, dof_ids, num_envs, device)
# parse configuration
if self.cfg.saturation_effort is not None:
self._saturation_effort = self.cfg.saturation_effort
else:
self._saturation_effort = torch.inf
# prepare joint vel buffer for max effort computation
self._dof_vel = torch.zeros_like(self.computed_effort)
# check that quantities are provided
if self.cfg.velocity_limit is None:
raise ValueError("The velocity limit must be provided for the DC motor actuator model.")
"""
Operations.
"""
def compute(
self, control_action: ArticulationActions, dof_pos: torch.Tensor, dof_vel: torch.Tensor
) -> ArticulationActions:
# save current joint vel
self._dof_vel[:] = dof_vel
# calculate the desired joint torques
return super().compute(control_action, dof_pos, dof_vel)
"""
Helper functions.
"""
def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor:
# compute torque limits
# -- max limit
max_effort = self.cfg.saturation_effort * (1.0 - self._dof_vel / self.velocity_limit)
max_effort = torch.clip(max_effort, min=0.0, max=self.effort_limit)
# -- min limit
min_effort = self.cfg.saturation_effort * (-1.0 - self._dof_vel / self.velocity_limit)
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=0.0)
# clip the torques based on the motor limits
return torch.clip(effort, min=min_effort, max=max_effort)
......@@ -10,9 +10,6 @@ The following actuator models are available:
* ANYdrive 3.x with DC actuator model.
* ANYdrive 3.0 (used on ANYmal-C) with LSTM actuator model.
The following actuator groups are available:
* ANYmal-C default actuator group that uses ANYdrive 3.0 with LSTM actuator model.
"""
from omni.isaac.orbit.actuators import ActuatorNetLSTMCfg, DCMotorCfg
......
......@@ -94,7 +94,7 @@ ANYMAL_B_CFG = LeggedRobotCfg(
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
actuators={"legs": Anydrive3LSTMCfg(dof_name_expr=[".*HAA", ".*HFE", ".*KFE"])},
actuators={"legs": Anydrive3LSTMCfg(dof_names_expr=[".*HAA", ".*HFE", ".*KFE"])},
)
"""Configuration of ANYmal-B robot using actuator-net."""
......@@ -145,6 +145,6 @@ ANYMAL_C_CFG = LeggedRobotCfg(
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
actuators={"legs": Anydrive3LSTMCfg(dof_name_expr=[".*HAA", ".*HFE", ".*KFE"])},
actuators={"legs": Anydrive3LSTMCfg(dof_names_expr=[".*HAA", ".*HFE", ".*KFE"])},
)
"""Configuration of ANYmal-C robot using actuator-net."""
......@@ -55,7 +55,7 @@ class RobotBase:
# Flag to check that instance is spawned.
self._is_spawned = False
# data for storing actuator group
self.actuators = dict.fromkeys(self.cfg.actuators.keys())
self.actuators: dict[str, ActuatorBase] = dict.fromkeys(self.cfg.actuators.keys())
"""
Properties
......@@ -527,7 +527,7 @@ class RobotBase:
# iterate over all actuator configurations
for actuator_name, actuator_cfg in self.cfg.actuators.items():
# create actuator group
dof_ids, dof_names = self.find_dofs(actuator_cfg.dof_name_expr)
dof_ids, dof_names = self.find_dofs(actuator_cfg.dof_names_expr)
# for efficiency avoid indexing over all indices
if len(dof_ids) == self.num_dof:
dof_ids = ...
......@@ -552,7 +552,7 @@ class RobotBase:
self.set_dof_torque_limit(1.0e9, dof_ids=actuator.dof_indices)
# perform some sanity checks to ensure actuators are prepared correctly
total_act_dof = sum(group.num_actuators for group in self.actuators.values())
total_act_dof = sum(group.num_joints for group in self.actuators.values())
if total_act_dof != self.num_dof:
carb.log_warn(
f"Not all actuators are configured through groups! Total number of actuated DOFs not equal to number of DOFs available: {total_act_dof} != {self.num_dof}."
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment