From c7fef1eec45e5942721505fbcc364d83cfe40e84 Mon Sep 17 00:00:00 2001 From: James Tigue Date: Thu, 9 Jan 2025 12:58:36 -0500 Subject: [PATCH] update velocity_limit docstring and clean up test_articulation --- .../omni.isaac.lab/omni/isaac/lab/actuators/actuator_cfg.py | 6 ++++++ .../omni.isaac.lab/test/assets/test_articulation.py | 4 ---- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/actuators/actuator_cfg.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/actuators/actuator_cfg.py index b2e4776638..0b2092a7e0 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/actuators/actuator_cfg.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/actuators/actuator_cfg.py @@ -41,6 +41,11 @@ class ActuatorBaseCfg: """Velocity limit of the joints in the group. Defaults to None. This limit is used by the actuator model. If None, the limit is set to the value specified in the USD joint prim. + + .. note:: + + velocity_limit is not used in ActuatorBaseCfg but is provided for inherited version like + :class:`omni.isaac.lab.actuators.DCMotor`. """ effort_limit_sim: dict[str, float] | float | None = None @@ -55,6 +60,7 @@ class ActuatorBaseCfg: If None, the limit is set to the value specified in the USD joint prim. Resulting solver solutions will constrain velocities by these limits. If velocity limits are too tight issues with solver convergence may occur. + """ stiffness: dict[str, float] | float | None = MISSING diff --git a/source/extensions/omni.isaac.lab/test/assets/test_articulation.py b/source/extensions/omni.isaac.lab/test/assets/test_articulation.py index 97f3ff4934..ba32aaae50 100644 --- a/source/extensions/omni.isaac.lab/test/assets/test_articulation.py +++ b/source/extensions/omni.isaac.lab/test/assets/test_articulation.py @@ -43,8 +43,6 @@ def generate_articulation_cfg( articulation_type: Literal["humanoid", "panda", "anymal", "shadow_hand", "single_joint"], stiffness: float | None = 10.0, damping: float | None = 2.0, - vel_limit: float | None = 100.0, - effort_limit: float | None = 400.0, vel_limit_sim: float | None = None, effort_limit_sim: float | None = None, ) -> ArticulationCfg: @@ -77,8 +75,6 @@ def generate_articulation_cfg( actuators={ "joint": ImplicitActuatorCfg( joint_names_expr=[".*"], - effort_limit=effort_limit, - velocity_limit=vel_limit, effort_limit_sim=effort_limit_sim, velocity_limit_sim=vel_limit_sim, stiffness=0.0,