Commit c907fa6c authored by ooctipus's avatar ooctipus Committed by Kelly Guo

Fixes implicit actuator limits configs for assets (#2952)

As discussed by several earlier commit and issues #2135 #1654 #1384
limit(velocity_limit), effort limit(effort_limit), simulation velocity
limit(velocity_limit_sim) and effort limit(effort_limit_sim).

ImplicitActuator, lacking the motor model, is inherently
non-attributable to velocity_limit or effort_limit, and should be using
velocity_limit_sim and effort_limit_sim instead if such limits should be
set. However, since most of environment with `ImplicitActuatorCfg` was
written before v1.4, when velocity_limit was basically ignored, and
velocity_limit_sim did not exist. To not break those environments
training, we remove all `velocity_limit` attribute from existing
`ImplicitActuatorCfg`, change all `effort_limit` to `effort_limit_sim`,
and added documentation to articulate this point .

However, even with removing velocity_limit, effort_limit, there could be
subtitles interacting with default USD value. USD may have joints that
comes with velocity_limit_sim and effort_limit_sim unnoticed by user.
Thus, user may thinking sim_limits are uncaped by not specifying limits
in Cfg, but is silently set in USD.

To make that more clear, this PR added flag:
`actuator_value_resolution_debug_print(default to false)` in
`ArticulationCfg`
that has following behavior:

case 1: if USD has default, ActuatorCfg has limits
       >if limits is same -> we are all good, no warning.
       >if limits is different -> we warn user we used cfg value.
case 2: USD has default, ActuatorCfg no limits -> We warn user saying
the USD defaults is used

Note that his logging can apply to all other joint attributes where
there could be USD-ArticulationCfg conflicts, not limited to
`velocity_limit_si,` or `effort_limit_sim` -> such as : stiffness,
damping, armature .....

 Note this section is also documented in articulation.rst
This PR added actuator discrepancy logging into the
:class:`ActuatorBase`.

<!-- As you go through the list, delete the ones that are not
applicable. -->

- Bug fix (non-breaking change which fixes an issue)
- This change requires a documentation update

Please attach before and after screenshots of the change if applicable.

<!--
Example:

| Before | After |
| ------ | ----- |
| _gif/png before_ | _gif/png after_ |

To upload images to a PR -- simply drag and drop an image while in edit
mode and it should upload the image directly. You can then paste that
source into the above before/after sections.
-->

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] 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
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

<!--
As you go through the checklist above, you can mark something as done by
putting an x character in it

For example,
- [x] I have done this task
- [ ] I have not done this task
-->

---------
Co-authored-by: 's avatarKelly Guo <kellyg@nvidia.com>
parent f2bc4bf2
...@@ -115,3 +115,154 @@ to combine them into a single actuator model. ...@@ -115,3 +115,154 @@ to combine them into a single actuator model.
damping={"slider_to_cart": 10.0, "cart_to_pole": 0.0}, damping={"slider_to_cart": 10.0, "cart_to_pole": 0.0},
), ),
}, },
ActuatorCfg velocity/effort limits considerations
-------------------------------------------------
In IsaacLab v1.4.0, the plain ``velocity_limit`` and ``effort_limit`` attributes were **not** consistently
pushed into the physics solver:
- **Implicit actuators**
- velocity_limit was ignored (never set in simulation)
- effort_limit was set into simulation
- **Explicit actuators**
- both velocity_limit and effort_limit were used only by the drive model, not by the solver
In v2.0.1 we accidentally changed this: all velocity_limit & effort_limit, implicit or
explicit, were being applied to the solver. That caused many training under the old default uncaped solver
limits to break.
To restore the original behavior while still giving users full control over solver limits, we introduced two new flags:
* **velocity_limit_sim**
Sets the physics-solver's maximum joint-velocity cap in simulation.
* **effort_limit_sim**
Sets the physics-solver's maximum joint-effort cap in simulation.
These explicitly set the solver's joint-velocity and joint-effort caps at simulation level.
On the other hand, velocity_limit and effort_limit model the motor's hardware-level constraints in torque
computation for all explicit actuators rather than limiting simulation-level constraint.
For implicit actuators, since they do not model motor hardware limitations, ``velocity_limit`` were removed in v2.1.1
and marked as deprecated. This preserves same behavior as they did in v1.4.0. Eventually, ``velocity_limit`` and
``effort_limit`` will be deprecated for implicit actuators, preserving only ``velocity_limit_sim`` and
``effort_limit_sim``
.. table:: Limit Options Comparison
.. list-table::
:header-rows: 1
:widths: 20 40 40
* - **Attribute**
- **Implicit Actuator**
- **Explicit Actuator**
* - ``velocity_limit``
- Deprecated (alias for ``velocity_limit_sim``)
- Used by the model (e.g. DC motor), not set into simulation
* - ``effort_limit``
- Deprecated (alias for ``effort_limit_sim``)
- Used by the model, not set into simulation
* - ``velocity_limit_sim``
- Set into simulation
- Set into simulation
* - ``effort_limit_sim``
- Set into simulation
- Set into simulation
Users who want to tune the underlying physics-solver limits should set the ``_sim`` flags.
USD vs. ActuatorCfg discrepancy resolution
------------------------------------------
USD having default value and the fact that ActuatorCfg can be specified with None, or a overriding value can sometime be
confusing what exactly gets written into simulation. The resolution follows these simple rules,per joint and per
property:
.. table:: Resolution Rules for USD vs. ActuatorCfg
+------------------------+------------------------+--------------------+
| **Condition** | **ActuatorCfg Value** | **Applied** |
+========================+========================+====================+
| No override provided | Not Specified | USD Value |
+------------------------+------------------------+--------------------+
| Override provided | User's ActuatorCfg | Same as ActuatorCfg|
+------------------------+------------------------+--------------------+
Digging into USD can sometime be unconvinent, to help clarify what exact value is written, we designed a flag
:attr:`~isaaclab.assets.ArticulationCfg.actuator_value_resolution_debug_print`,
to help user figure out what exact value gets used in simulation.
Whenever an actuator parameter is overridden in the user's ActuatorCfg (or left unspecified),
we compare it to the value read from the USD definition and record any differences. For each joint and each property,
if unmatching value is found, we log the resolution:
1. **USD Value**
The default limit or gain parsed from the USD asset.
2. **ActuatorCfg Value**
The user-provided override (or “Not Specified” if none was given).
3. **Applied**
The final value actually used for simulation: if the user didn't override it, this matches the USD value;
otherwise it reflects the user's setting.
This resolution info is emitted as a warning table only when discrepancies exist.
Here's an example of what you'll see::
+----------------+--------------------+---------------------+----+-------------+--------------------+----------+
| Group | Property | Name | ID | USD Value | ActuatorCfg Value | Applied |
+----------------+--------------------+---------------------+----+-------------+--------------------+----------+
| panda_shoulder | velocity_limit_sim | panda_joint1 | 0 | 2.17e+00 | Not Specified | 2.17e+00 |
| | | panda_joint2 | 1 | 2.17e+00 | Not Specified | 2.17e+00 |
| | | panda_joint3 | 2 | 2.17e+00 | Not Specified | 2.17e+00 |
| | | panda_joint4 | 3 | 2.17e+00 | Not Specified | 2.17e+00 |
| | stiffness | panda_joint1 | 0 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | | panda_joint2 | 1 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | | panda_joint3 | 2 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | | panda_joint4 | 3 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | damping | panda_joint1 | 0 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | | panda_joint2 | 1 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | | panda_joint3 | 2 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | | panda_joint4 | 3 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | armature | panda_joint1 | 0 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint2 | 1 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint3 | 2 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint4 | 3 | 0.00e+00 | Not Specified | 0.00e+00 |
| panda_forearm | velocity_limit_sim | panda_joint5 | 4 | 2.61e+00 | Not Specified | 2.61e+00 |
| | | panda_joint6 | 5 | 2.61e+00 | Not Specified | 2.61e+00 |
| | | panda_joint7 | 6 | 2.61e+00 | Not Specified | 2.61e+00 |
| | stiffness | panda_joint5 | 4 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | | panda_joint6 | 5 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | | panda_joint7 | 6 | 2.29e+04 | 8.00e+01 | 8.00e+01 |
| | damping | panda_joint5 | 4 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | | panda_joint6 | 5 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | | panda_joint7 | 6 | 4.58e+03 | 4.00e+00 | 4.00e+00 |
| | armature | panda_joint5 | 4 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint6 | 5 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint7 | 6 | 0.00e+00 | Not Specified | 0.00e+00 |
| | friction | panda_joint5 | 4 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint6 | 5 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_joint7 | 6 | 0.00e+00 | Not Specified | 0.00e+00 |
| panda_hand | velocity_limit_sim | panda_finger_joint1 | 7 | 2.00e-01 | Not Specified | 2.00e-01 |
| | | panda_finger_joint2 | 8 | 2.00e-01 | Not Specified | 2.00e-01 |
| | stiffness | panda_finger_joint1 | 7 | 1.00e+06 | 2.00e+03 | 2.00e+03 |
| | | panda_finger_joint2 | 8 | 1.00e+06 | 2.00e+03 | 2.00e+03 |
| | armature | panda_finger_joint1 | 7 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_finger_joint2 | 8 | 0.00e+00 | Not Specified | 0.00e+00 |
| | friction | panda_finger_joint1 | 7 | 0.00e+00 | Not Specified | 0.00e+00 |
| | | panda_finger_joint2 | 8 | 0.00e+00 | Not Specified | 0.00e+00 |
+----------------+--------------------+---------------------+----+-------------+--------------------+----------+
To keep the cleaniness of logging, :attr:`~isaaclab.assets.ArticulationCfg.actuator_value_resolution_debug_print`
default to False, remember to turn it on when wishes.
...@@ -692,18 +692,18 @@ the need to set simulation parameters for actors in the task implementation. ...@@ -692,18 +692,18 @@ the need to set simulation parameters for actors in the task implementation.
| asset_root = os.path.dirname(asset_path) | actuators={ | | asset_root = os.path.dirname(asset_path) | actuators={ |
| asset_file = os.path.basename(asset_path) | "cart_actuator": ImplicitActuatorCfg( | | asset_file = os.path.basename(asset_path) | "cart_actuator": ImplicitActuatorCfg( |
| | joint_names_expr=["slider_to_cart"], | | | joint_names_expr=["slider_to_cart"], |
| asset_options = gymapi.AssetOptions() | effort_limit=400.0, | | asset_options = gymapi.AssetOptions() | effort_limit_sim=400.0, |
| asset_options.fix_base_link = True | velocity_limit=100.0, | | asset_options.fix_base_link = True | velocity_limit_sim=100.0, |
| cartpole_asset = self.gym.load_asset(self.sim, | stiffness=0.0, | | cartpole_asset = self.gym.load_asset(self.sim, | stiffness=0.0, |
| asset_root, asset_file, asset_options) | damping=10.0, | | asset_root, asset_file, asset_options) | damping=10.0, |
| self.num_dof = self.gym.get_asset_dof_count( | ), | | self.num_dof = self.gym.get_asset_dof_count( | ), |
| cartpole_asset) | "pole_actuator": ImplicitActuatorCfg( | | cartpole_asset) | "pole_actuator": ImplicitActuatorCfg( |
| | joint_names_expr=["cart_to_pole"], effort_limit=400.0, | | | joint_names_expr=["cart_to_pole"], |
| pose = gymapi.Transform() | velocity_limit=100.0, stiffness=0.0, damping=0.0 | | pose = gymapi.Transform() | effort_limit_sim=400.0, velocity_limit_sim=100.0, |
| if self.up_axis == 'z': | ), | | if self.up_axis == 'z': | stiffness=0.0, damping=0.0 |
| pose.p.z = 2.0 | }, | | pose.p.z = 2.0 | ), |
| pose.r = gymapi.Quat(0.0, 0.0, 0.0, 1.0) | ) | | pose.r = gymapi.Quat(0.0, 0.0, 0.0, 1.0) | }, |
| else: | | | else: | ) |
| pose.p.y = 2.0 | | | pose.p.y = 2.0 | |
| pose.r = gymapi.Quat( | | | pose.r = gymapi.Quat( | |
| -np.sqrt(2)/2, 0.0, 0.0, np.sqrt(2)/2) | | | -np.sqrt(2)/2, 0.0, 0.0, np.sqrt(2)/2) | |
......
...@@ -295,8 +295,8 @@ including file path, simulation parameters, actuator properties, and initial sta ...@@ -295,8 +295,8 @@ including file path, simulation parameters, actuator properties, and initial sta
actuators={ actuators={
"cart_actuator": ImplicitActuatorCfg( "cart_actuator": ImplicitActuatorCfg(
joint_names_expr=["slider_to_cart"], joint_names_expr=["slider_to_cart"],
effort_limit=400.0, effort_limit_sim=400.0,
velocity_limit=100.0, velocity_limit_sim=100.0,
stiffness=0.0, stiffness=0.0,
damping=10.0, damping=10.0,
), ),
......
...@@ -156,26 +156,46 @@ class ActuatorBase(ABC): ...@@ -156,26 +156,46 @@ class ActuatorBase(ABC):
self._device = device self._device = device
self._joint_names = joint_names self._joint_names = joint_names
self._joint_indices = joint_ids self._joint_indices = joint_ids
self.joint_property_resolution_table: dict[str, list] = {}
# For explicit models, we do not want to enforce the effort limit through the solver # For explicit models, we do not want to enforce the effort limit through the solver
# (unless it is explicitly set) # (unless it is explicitly set)
if not self.is_implicit_model and self.cfg.effort_limit_sim is None: if not self.is_implicit_model and self.cfg.effort_limit_sim is None:
self.cfg.effort_limit_sim = self._DEFAULT_MAX_EFFORT_SIM self.cfg.effort_limit_sim = self._DEFAULT_MAX_EFFORT_SIM
# parse joint stiffness and damping # resolve usd, actuator configuration values
self.stiffness = self._parse_joint_parameter(self.cfg.stiffness, stiffness) # case 1: if usd_value == actuator_cfg_value: all good,
self.damping = self._parse_joint_parameter(self.cfg.damping, damping) # case 2: if usd_value != actuator_cfg_value: we use actuator_cfg_value
# parse joint armature and friction # case 3: if actuator_cfg_value is None: we use usd_value
self.armature = self._parse_joint_parameter(self.cfg.armature, armature)
self.friction = self._parse_joint_parameter(self.cfg.friction, friction) to_check = [
self.dynamic_friction = self._parse_joint_parameter(self.cfg.dynamic_friction, dynamic_friction) ("velocity_limit_sim", velocity_limit),
self.viscous_friction = self._parse_joint_parameter(self.cfg.viscous_friction, viscous_friction) ("effort_limit_sim", effort_limit),
# parse joint limits ("stiffness", stiffness),
# -- velocity ("damping", damping),
self.velocity_limit_sim = self._parse_joint_parameter(self.cfg.velocity_limit_sim, velocity_limit) ("armature", armature),
("friction", friction),
("dynamic_friction", dynamic_friction),
("viscous_friction", viscous_friction),
]
for param_name, usd_val in to_check:
cfg_val = getattr(self.cfg, param_name)
setattr(self, param_name, self._parse_joint_parameter(cfg_val, usd_val))
new_val = getattr(self, param_name)
allclose = (
torch.all(new_val == usd_val) if isinstance(usd_val, (float, int)) else torch.allclose(new_val, usd_val)
)
if cfg_val is None or not allclose:
self._record_actuator_resolution(
cfg_val=getattr(self.cfg, param_name),
new_val=new_val[0], # new val always has the shape of (num_envs, num_joints)
usd_val=usd_val,
joint_names=joint_names,
joint_ids=joint_ids,
actuator_param=param_name,
)
self.velocity_limit = self._parse_joint_parameter(self.cfg.velocity_limit, self.velocity_limit_sim) self.velocity_limit = self._parse_joint_parameter(self.cfg.velocity_limit, self.velocity_limit_sim)
# -- effort
self.effort_limit_sim = self._parse_joint_parameter(self.cfg.effort_limit_sim, effort_limit)
self.effort_limit = self._parse_joint_parameter(self.cfg.effort_limit, self.effort_limit_sim) self.effort_limit = self._parse_joint_parameter(self.cfg.effort_limit, self.effort_limit_sim)
# create commands buffers for allocation # create commands buffers for allocation
...@@ -260,6 +280,18 @@ class ActuatorBase(ABC): ...@@ -260,6 +280,18 @@ class ActuatorBase(ABC):
Helper functions. Helper functions.
""" """
def _record_actuator_resolution(self, cfg_val, new_val, usd_val, joint_names, joint_ids, actuator_param: str):
if actuator_param not in self.joint_property_resolution_table:
self.joint_property_resolution_table[actuator_param] = []
table = self.joint_property_resolution_table[actuator_param]
ids = joint_ids if isinstance(joint_ids, torch.Tensor) else list(range(len(joint_names)))
for idx, name in enumerate(joint_names):
cfg_val_log = "Not Specified" if cfg_val is None else float(new_val[idx])
default_usd_val = usd_val if isinstance(usd_val, (float, int)) else float(usd_val[0][idx])
applied_val_log = default_usd_val if cfg_val is None else float(new_val[idx])
table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log])
def _parse_joint_parameter( def _parse_joint_parameter(
self, cfg_value: float | dict[str, float] | None, default_value: float | torch.Tensor | None self, cfg_value: float | dict[str, float] | None, default_value: float | torch.Tensor | None
) -> torch.Tensor: ) -> torch.Tensor:
......
...@@ -1717,8 +1717,21 @@ class Articulation(AssetBase): ...@@ -1717,8 +1717,21 @@ class Articulation(AssetBase):
f" joints available: {total_act_joints} != {self.num_joints - self.num_fixed_tendons}." f" joints available: {total_act_joints} != {self.num_joints - self.num_fixed_tendons}."
) )
if self.cfg.actuator_value_resolution_debug_print:
t = PrettyTable(["Group", "Property", "Name", "ID", "USD Value", "ActutatorCfg Value", "Applied"])
for actuator_group, actuator in self.actuators.items():
group_count = 0
for property, resolution_details in actuator.joint_property_resolution_table.items():
for prop_idx, resolution_detail in enumerate(resolution_details):
actuator_group_str = actuator_group if group_count == 0 else ""
property_str = property if prop_idx == 0 else ""
fmt = [f"{v:.2e}" if isinstance(v, float) else str(v) for v in resolution_detail]
t.add_row([actuator_group_str, property_str, *fmt])
group_count += 1
omni.log.warn(f"\nActuatorCfg-USD Value Discrepancy Resolution (matching values are skipped): \n{t}")
def _process_tendons(self): def _process_tendons(self):
"""Process fixed and spatialtendons.""" """Process fixed and spatial tendons."""
# create a list to store the fixed tendon names # create a list to store the fixed tendon names
self._fixed_tendon_names = list() self._fixed_tendon_names = list()
self._spatial_tendon_names = list() self._spatial_tendon_names = list()
......
...@@ -66,3 +66,7 @@ class ArticulationCfg(AssetBaseCfg): ...@@ -66,3 +66,7 @@ class ArticulationCfg(AssetBaseCfg):
actuators: dict[str, ActuatorBaseCfg] = MISSING actuators: dict[str, ActuatorBaseCfg] = MISSING
"""Actuators for the robot with corresponding joint names.""" """Actuators for the robot with corresponding joint names."""
actuator_value_resolution_debug_print = False
"""Print the resolution of actuator final value when input cfg is different from USD value, Defaults to False
"""
...@@ -906,6 +906,7 @@ def test_external_force_on_single_body_at_position(sim, num_articulations, devic ...@@ -906,6 +906,7 @@ def test_external_force_on_single_body_at_position(sim, num_articulations, devic
for _ in range(5): for _ in range(5):
# reset root state # reset root state
root_state = articulation.data.default_root_state.clone() root_state = articulation.data.default_root_state.clone()
root_state[0, 0] = 2.5 # space them apart by 2.5m
articulation.write_root_pose_to_sim(root_state[:, :7]) articulation.write_root_pose_to_sim(root_state[:, :7])
articulation.write_root_velocity_to_sim(root_state[:, 7:]) articulation.write_root_velocity_to_sim(root_state[:, 7:])
......
...@@ -58,8 +58,7 @@ ALLEGRO_HAND_CFG = ArticulationCfg( ...@@ -58,8 +58,7 @@ ALLEGRO_HAND_CFG = ArticulationCfg(
actuators={ actuators={
"fingers": ImplicitActuatorCfg( "fingers": ImplicitActuatorCfg(
joint_names_expr=[".*"], joint_names_expr=[".*"],
effort_limit=0.5, effort_limit_sim=0.5,
velocity_limit=100.0,
stiffness=3.0, stiffness=3.0,
damping=0.1, damping=0.1,
friction=0.01, friction=0.01,
......
...@@ -39,16 +39,15 @@ CART_DOUBLE_PENDULUM_CFG = ArticulationCfg( ...@@ -39,16 +39,15 @@ CART_DOUBLE_PENDULUM_CFG = ArticulationCfg(
actuators={ actuators={
"cart_actuator": ImplicitActuatorCfg( "cart_actuator": ImplicitActuatorCfg(
joint_names_expr=["slider_to_cart"], joint_names_expr=["slider_to_cart"],
effort_limit=400.0, effort_limit_sim=400.0,
velocity_limit=100.0,
stiffness=0.0, stiffness=0.0,
damping=10.0, damping=10.0,
), ),
"pole_actuator": ImplicitActuatorCfg( "pole_actuator": ImplicitActuatorCfg(
joint_names_expr=["cart_to_pole"], effort_limit=400.0, velocity_limit=100.0, stiffness=0.0, damping=0.0 joint_names_expr=["cart_to_pole"], effort_limit_sim=400.0, stiffness=0.0, damping=0.0
), ),
"pendulum_actuator": ImplicitActuatorCfg( "pendulum_actuator": ImplicitActuatorCfg(
joint_names_expr=["pole_to_pendulum"], effort_limit=400.0, velocity_limit=100.0, stiffness=0.0, damping=0.0 joint_names_expr=["pole_to_pendulum"], effort_limit_sim=400.0, stiffness=0.0, damping=0.0
), ),
}, },
) )
......
...@@ -39,13 +39,12 @@ CARTPOLE_CFG = ArticulationCfg( ...@@ -39,13 +39,12 @@ CARTPOLE_CFG = ArticulationCfg(
actuators={ actuators={
"cart_actuator": ImplicitActuatorCfg( "cart_actuator": ImplicitActuatorCfg(
joint_names_expr=["slider_to_cart"], joint_names_expr=["slider_to_cart"],
effort_limit=400.0, effort_limit_sim=400.0,
velocity_limit=100.0,
stiffness=0.0, stiffness=0.0,
damping=10.0, damping=10.0,
), ),
"pole_actuator": ImplicitActuatorCfg( "pole_actuator": ImplicitActuatorCfg(
joint_names_expr=["cart_to_pole"], effort_limit=400.0, velocity_limit=100.0, stiffness=0.0, damping=0.0 joint_names_expr=["cart_to_pole"], effort_limit_sim=400.0, stiffness=0.0, damping=0.0
), ),
}, },
) )
......
...@@ -60,8 +60,7 @@ CASSIE_CFG = ArticulationCfg( ...@@ -60,8 +60,7 @@ CASSIE_CFG = ArticulationCfg(
actuators={ actuators={
"legs": ImplicitActuatorCfg( "legs": ImplicitActuatorCfg(
joint_names_expr=["hip_.*", "thigh_.*", "ankle_.*"], joint_names_expr=["hip_.*", "thigh_.*", "ankle_.*"],
effort_limit=200.0, effort_limit_sim=200.0,
velocity_limit=10.0,
stiffness={ stiffness={
"hip_abduction.*": 100.0, "hip_abduction.*": 100.0,
"hip_rotation.*": 100.0, "hip_rotation.*": 100.0,
...@@ -79,8 +78,7 @@ CASSIE_CFG = ArticulationCfg( ...@@ -79,8 +78,7 @@ CASSIE_CFG = ArticulationCfg(
), ),
"toes": ImplicitActuatorCfg( "toes": ImplicitActuatorCfg(
joint_names_expr=["toe_.*"], joint_names_expr=["toe_.*"],
effort_limit=20.0, effort_limit_sim=20.0,
velocity_limit=10.0,
stiffness={ stiffness={
"toe_joint.*": 20.0, "toe_joint.*": 20.0,
}, },
......
...@@ -51,21 +51,18 @@ FRANKA_PANDA_CFG = ArticulationCfg( ...@@ -51,21 +51,18 @@ FRANKA_PANDA_CFG = ArticulationCfg(
"panda_shoulder": ImplicitActuatorCfg( "panda_shoulder": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[1-4]"], joint_names_expr=["panda_joint[1-4]"],
effort_limit_sim=87.0, effort_limit_sim=87.0,
velocity_limit_sim=2.175,
stiffness=80.0, stiffness=80.0,
damping=4.0, damping=4.0,
), ),
"panda_forearm": ImplicitActuatorCfg( "panda_forearm": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"], joint_names_expr=["panda_joint[5-7]"],
effort_limit_sim=12.0, effort_limit_sim=12.0,
velocity_limit_sim=2.61,
stiffness=80.0, stiffness=80.0,
damping=4.0, damping=4.0,
), ),
"panda_hand": ImplicitActuatorCfg( "panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint.*"], joint_names_expr=["panda_finger_joint.*"],
effort_limit_sim=200.0, effort_limit_sim=200.0,
velocity_limit_sim=0.2,
stiffness=2e3, stiffness=2e3,
damping=1e2, damping=1e2,
), ),
......
...@@ -51,8 +51,7 @@ KINOVA_JACO2_N7S300_CFG = ArticulationCfg( ...@@ -51,8 +51,7 @@ KINOVA_JACO2_N7S300_CFG = ArticulationCfg(
actuators={ actuators={
"arm": ImplicitActuatorCfg( "arm": ImplicitActuatorCfg(
joint_names_expr=[".*_joint_[1-7]"], joint_names_expr=[".*_joint_[1-7]"],
velocity_limit=100.0, effort_limit_sim={
effort_limit={
".*_joint_[1-2]": 80.0, ".*_joint_[1-2]": 80.0,
".*_joint_[3-4]": 40.0, ".*_joint_[3-4]": 40.0,
".*_joint_[5-7]": 20.0, ".*_joint_[5-7]": 20.0,
...@@ -68,8 +67,7 @@ KINOVA_JACO2_N7S300_CFG = ArticulationCfg( ...@@ -68,8 +67,7 @@ KINOVA_JACO2_N7S300_CFG = ArticulationCfg(
), ),
"gripper": ImplicitActuatorCfg( "gripper": ImplicitActuatorCfg(
joint_names_expr=[".*_finger_[1-3]", ".*_finger_tip_[1-3]"], joint_names_expr=[".*_finger_[1-3]", ".*_finger_tip_[1-3]"],
velocity_limit=100.0, effort_limit_sim=2.0,
effort_limit=2.0,
stiffness=1.2, stiffness=1.2,
damping=0.01, damping=0.01,
), ),
...@@ -105,8 +103,7 @@ KINOVA_JACO2_N6S300_CFG = ArticulationCfg( ...@@ -105,8 +103,7 @@ KINOVA_JACO2_N6S300_CFG = ArticulationCfg(
actuators={ actuators={
"arm": ImplicitActuatorCfg( "arm": ImplicitActuatorCfg(
joint_names_expr=[".*_joint_[1-6]"], joint_names_expr=[".*_joint_[1-6]"],
velocity_limit=100.0, effort_limit_sim={
effort_limit={
".*_joint_[1-2]": 80.0, ".*_joint_[1-2]": 80.0,
".*_joint_3": 40.0, ".*_joint_3": 40.0,
".*_joint_[4-6]": 20.0, ".*_joint_[4-6]": 20.0,
...@@ -122,8 +119,7 @@ KINOVA_JACO2_N6S300_CFG = ArticulationCfg( ...@@ -122,8 +119,7 @@ KINOVA_JACO2_N6S300_CFG = ArticulationCfg(
), ),
"gripper": ImplicitActuatorCfg( "gripper": ImplicitActuatorCfg(
joint_names_expr=[".*_finger_[1-3]", ".*_finger_tip_[1-3]"], joint_names_expr=[".*_finger_[1-3]", ".*_finger_tip_[1-3]"],
velocity_limit=100.0, effort_limit_sim=2.0,
effort_limit=2.0,
stiffness=1.2, stiffness=1.2,
damping=0.01, damping=0.01,
), ),
...@@ -158,7 +154,6 @@ KINOVA_GEN3_N7_CFG = ArticulationCfg( ...@@ -158,7 +154,6 @@ KINOVA_GEN3_N7_CFG = ArticulationCfg(
actuators={ actuators={
"arm": ImplicitActuatorCfg( "arm": ImplicitActuatorCfg(
joint_names_expr=["joint_[1-7]"], joint_names_expr=["joint_[1-7]"],
velocity_limit=100.0,
effort_limit={ effort_limit={
"joint_[1-4]": 39.0, "joint_[1-4]": 39.0,
"joint_[5-7]": 9.0, "joint_[5-7]": 9.0,
......
...@@ -49,29 +49,25 @@ RIDGEBACK_FRANKA_PANDA_CFG = ArticulationCfg( ...@@ -49,29 +49,25 @@ RIDGEBACK_FRANKA_PANDA_CFG = ArticulationCfg(
actuators={ actuators={
"base": ImplicitActuatorCfg( "base": ImplicitActuatorCfg(
joint_names_expr=["dummy_base_.*"], joint_names_expr=["dummy_base_.*"],
velocity_limit=100.0, effort_limit_sim=1000.0,
effort_limit=1000.0,
stiffness=0.0, stiffness=0.0,
damping=1e5, damping=1e5,
), ),
"panda_shoulder": ImplicitActuatorCfg( "panda_shoulder": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[1-4]"], joint_names_expr=["panda_joint[1-4]"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=100.0,
stiffness=800.0, stiffness=800.0,
damping=40.0, damping=40.0,
), ),
"panda_forearm": ImplicitActuatorCfg( "panda_forearm": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"], joint_names_expr=["panda_joint[5-7]"],
effort_limit=12.0, effort_limit_sim=12.0,
velocity_limit=100.0,
stiffness=800.0, stiffness=800.0,
damping=40.0, damping=40.0,
), ),
"panda_hand": ImplicitActuatorCfg( "panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint.*"], joint_names_expr=["panda_finger_joint.*"],
effort_limit=200.0, effort_limit_sim=200.0,
velocity_limit=0.2,
stiffness=1e5, stiffness=1e5,
damping=1e3, damping=1e3,
), ),
......
...@@ -48,15 +48,13 @@ SAWYER_CFG = ArticulationCfg( ...@@ -48,15 +48,13 @@ SAWYER_CFG = ArticulationCfg(
actuators={ actuators={
"head": ImplicitActuatorCfg( "head": ImplicitActuatorCfg(
joint_names_expr=["head_pan"], joint_names_expr=["head_pan"],
velocity_limit=100.0, effort_limit_sim=8.0,
effort_limit=8.0,
stiffness=800.0, stiffness=800.0,
damping=40.0, damping=40.0,
), ),
"arm": ImplicitActuatorCfg( "arm": ImplicitActuatorCfg(
joint_names_expr=["right_j[0-6]"], joint_names_expr=["right_j[0-6]"],
velocity_limit=100.0, effort_limit_sim={
effort_limit={
"right_j[0-1]": 80.0, "right_j[0-1]": 80.0,
"right_j[2-3]": 40.0, "right_j[2-3]": 40.0,
"right_j[4-6]": 9.0, "right_j[4-6]": 9.0,
......
...@@ -53,7 +53,7 @@ SHADOW_HAND_CFG = ArticulationCfg( ...@@ -53,7 +53,7 @@ SHADOW_HAND_CFG = ArticulationCfg(
actuators={ actuators={
"fingers": ImplicitActuatorCfg( "fingers": ImplicitActuatorCfg(
joint_names_expr=["robot0_WR.*", "robot0_(FF|MF|RF|LF|TH)J(3|2|1)", "robot0_(LF|TH)J4", "robot0_THJ0"], joint_names_expr=["robot0_WR.*", "robot0_(FF|MF|RF|LF|TH)J(3|2|1)", "robot0_(LF|TH)J4", "robot0_THJ0"],
effort_limit={ effort_limit_sim={
"robot0_WRJ1": 4.785, "robot0_WRJ1": 4.785,
"robot0_WRJ0": 2.175, "robot0_WRJ0": 2.175,
"robot0_(FF|MF|RF|LF)J1": 0.7245, "robot0_(FF|MF|RF|LF)J1": 0.7245,
......
...@@ -216,8 +216,7 @@ H1_CFG = ArticulationCfg( ...@@ -216,8 +216,7 @@ H1_CFG = ArticulationCfg(
actuators={ actuators={
"legs": ImplicitActuatorCfg( "legs": ImplicitActuatorCfg(
joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee", "torso"], joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee", "torso"],
effort_limit=300, effort_limit_sim=300,
velocity_limit=100.0,
stiffness={ stiffness={
".*_hip_yaw": 150.0, ".*_hip_yaw": 150.0,
".*_hip_roll": 150.0, ".*_hip_roll": 150.0,
...@@ -235,15 +234,13 @@ H1_CFG = ArticulationCfg( ...@@ -235,15 +234,13 @@ H1_CFG = ArticulationCfg(
), ),
"feet": ImplicitActuatorCfg( "feet": ImplicitActuatorCfg(
joint_names_expr=[".*_ankle"], joint_names_expr=[".*_ankle"],
effort_limit=100, effort_limit_sim=100,
velocity_limit=100.0,
stiffness={".*_ankle": 20.0}, stiffness={".*_ankle": 20.0},
damping={".*_ankle": 4.0}, damping={".*_ankle": 4.0},
), ),
"arms": ImplicitActuatorCfg( "arms": ImplicitActuatorCfg(
joint_names_expr=[".*_shoulder_pitch", ".*_shoulder_roll", ".*_shoulder_yaw", ".*_elbow"], joint_names_expr=[".*_shoulder_pitch", ".*_shoulder_roll", ".*_shoulder_yaw", ".*_elbow"],
effort_limit=300, effort_limit_sim=300,
velocity_limit=100.0,
stiffness={ stiffness={
".*_shoulder_pitch": 40.0, ".*_shoulder_pitch": 40.0,
".*_shoulder_roll": 40.0, ".*_shoulder_roll": 40.0,
...@@ -315,8 +312,7 @@ G1_CFG = ArticulationCfg( ...@@ -315,8 +312,7 @@ G1_CFG = ArticulationCfg(
".*_knee_joint", ".*_knee_joint",
"torso_joint", "torso_joint",
], ],
effort_limit=300, effort_limit_sim=300,
velocity_limit=100.0,
stiffness={ stiffness={
".*_hip_yaw_joint": 150.0, ".*_hip_yaw_joint": 150.0,
".*_hip_roll_joint": 150.0, ".*_hip_roll_joint": 150.0,
...@@ -338,7 +334,7 @@ G1_CFG = ArticulationCfg( ...@@ -338,7 +334,7 @@ G1_CFG = ArticulationCfg(
}, },
), ),
"feet": ImplicitActuatorCfg( "feet": ImplicitActuatorCfg(
effort_limit=20, effort_limit_sim=20,
joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"], joint_names_expr=[".*_ankle_pitch_joint", ".*_ankle_roll_joint"],
stiffness=20.0, stiffness=20.0,
damping=2.0, damping=2.0,
...@@ -359,8 +355,7 @@ G1_CFG = ArticulationCfg( ...@@ -359,8 +355,7 @@ G1_CFG = ArticulationCfg(
".*_one_joint", ".*_one_joint",
".*_two_joint", ".*_two_joint",
], ],
effort_limit=300, effort_limit_sim=300,
velocity_limit=100.0,
stiffness=40.0, stiffness=40.0,
damping=10.0, damping=10.0,
armature={ armature={
......
...@@ -44,8 +44,7 @@ UR10_CFG = ArticulationCfg( ...@@ -44,8 +44,7 @@ UR10_CFG = ArticulationCfg(
actuators={ actuators={
"arm": ImplicitActuatorCfg( "arm": ImplicitActuatorCfg(
joint_names_expr=[".*"], joint_names_expr=[".*"],
velocity_limit=100.0, effort_limit_sim=87.0,
effort_limit=87.0,
stiffness=800.0, stiffness=800.0,
damping=40.0, damping=40.0,
), ),
......
...@@ -163,8 +163,7 @@ class FactoryEnvCfg(DirectRLEnvCfg): ...@@ -163,8 +163,7 @@ class FactoryEnvCfg(DirectRLEnvCfg):
damping=0.0, damping=0.0,
friction=0.0, friction=0.0,
armature=0.0, armature=0.0,
effort_limit=87, effort_limit_sim=87,
velocity_limit=124.6,
), ),
"panda_arm2": ImplicitActuatorCfg( "panda_arm2": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"], joint_names_expr=["panda_joint[5-7]"],
...@@ -172,13 +171,11 @@ class FactoryEnvCfg(DirectRLEnvCfg): ...@@ -172,13 +171,11 @@ class FactoryEnvCfg(DirectRLEnvCfg):
damping=0.0, damping=0.0,
friction=0.0, friction=0.0,
armature=0.0, armature=0.0,
effort_limit=12, effort_limit_sim=12,
velocity_limit=149.5,
), ),
"panda_hand": ImplicitActuatorCfg( "panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint[1-2]"], joint_names_expr=["panda_finger_joint[1-2]"],
effort_limit=40.0, effort_limit_sim=40.0,
velocity_limit=0.04,
stiffness=7500.0, stiffness=7500.0,
damping=173.0, damping=173.0,
friction=0.1, friction=0.1,
......
...@@ -81,22 +81,19 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): ...@@ -81,22 +81,19 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg):
actuators={ actuators={
"panda_shoulder": ImplicitActuatorCfg( "panda_shoulder": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[1-4]"], joint_names_expr=["panda_joint[1-4]"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=2.175,
stiffness=80.0, stiffness=80.0,
damping=4.0, damping=4.0,
), ),
"panda_forearm": ImplicitActuatorCfg( "panda_forearm": ImplicitActuatorCfg(
joint_names_expr=["panda_joint[5-7]"], joint_names_expr=["panda_joint[5-7]"],
effort_limit=12.0, effort_limit_sim=12.0,
velocity_limit=2.61,
stiffness=80.0, stiffness=80.0,
damping=4.0, damping=4.0,
), ),
"panda_hand": ImplicitActuatorCfg( "panda_hand": ImplicitActuatorCfg(
joint_names_expr=["panda_finger_joint.*"], joint_names_expr=["panda_finger_joint.*"],
effort_limit=200.0, effort_limit_sim=200.0,
velocity_limit=0.2,
stiffness=2e3, stiffness=2e3,
damping=1e2, damping=1e2,
), ),
...@@ -123,15 +120,13 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): ...@@ -123,15 +120,13 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg):
actuators={ actuators={
"drawers": ImplicitActuatorCfg( "drawers": ImplicitActuatorCfg(
joint_names_expr=["drawer_top_joint", "drawer_bottom_joint"], joint_names_expr=["drawer_top_joint", "drawer_bottom_joint"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=100.0,
stiffness=10.0, stiffness=10.0,
damping=1.0, damping=1.0,
), ),
"doors": ImplicitActuatorCfg( "doors": ImplicitActuatorCfg(
joint_names_expr=["door_left_joint", "door_right_joint"], joint_names_expr=["door_left_joint", "door_right_joint"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=100.0,
stiffness=10.0, stiffness=10.0,
damping=2.5, damping=2.5,
), ),
......
...@@ -71,15 +71,13 @@ class CabinetSceneCfg(InteractiveSceneCfg): ...@@ -71,15 +71,13 @@ class CabinetSceneCfg(InteractiveSceneCfg):
actuators={ actuators={
"drawers": ImplicitActuatorCfg( "drawers": ImplicitActuatorCfg(
joint_names_expr=["drawer_top_joint", "drawer_bottom_joint"], joint_names_expr=["drawer_top_joint", "drawer_bottom_joint"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=100.0,
stiffness=10.0, stiffness=10.0,
damping=1.0, damping=1.0,
), ),
"doors": ImplicitActuatorCfg( "doors": ImplicitActuatorCfg(
joint_names_expr=["door_left_joint", "door_right_joint"], joint_names_expr=["door_left_joint", "door_right_joint"],
effort_limit=87.0, effort_limit_sim=87.0,
velocity_limit=100.0,
stiffness=10.0, stiffness=10.0,
damping=2.5, damping=2.5,
), ),
......
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