Skip to content

Add joint effort limit parsing when importing from URDF#2244

Merged
eric-heiden merged 5 commits intonewton-physics:mainfrom
kwang-12:pr-effort-limit
Apr 7, 2026
Merged

Add joint effort limit parsing when importing from URDF#2244
eric-heiden merged 5 commits intonewton-physics:mainfrom
kwang-12:pr-effort-limit

Conversation

@kwang-12
Copy link
Copy Markdown
Contributor

@kwang-12 kwang-12 commented Mar 27, 2026

Description

This PR updates the URDF importer to read joint <limit effort="..."> values and forward them into imported revolute and prismatic joints via effort_limit.

Previously, URDF import preserved joint position limits but ignored effort limits, so imported joints silently fell back to the builder default. With this change, URDF-authored effort limits are applied during joint creation, while joints that omit effort continue to inherit builder.default_joint_cfg.effort_limit.

Checklist

  • New or existing tests cover these changes
  • The documentation is up to date with these changes
  • CHANGELOG.md has been updated (if user-facing change)

Test plan

Added coverage in newton.tests.test_import_urdf.TestImportUrdfBasic.test_revolute_joint_urdf to verify that a URDF joint with effort="6.78" is imported with the expected builder.joint_effort_limit.

Verify with:

python -m unittest newton.tests.test_import_urdf.TestImportUrdfBasic.test_revolute_joint_urdf

New feature / API change

import newton

urdf = """
<robot name="effort_limit_test">
    <link name="base_link"/>
    <link name="child_link"/>
    <joint name="slider" type="prismatic">
        <parent link="base_link"/>
        <child link="child_link"/>
        <axis xyz="1 0 0"/>
        <limit lower="0.0" upper="0.5" effort="12.5"/>
    </joint>
</robot>
"""

builder = newton.ModelBuilder()
builder.add_urdf(urdf)

# Imported from the URDF <limit effort="..."> attribute.
print(builder.joint_effort_limit[-1])  # 12.5

Summary by CodeRabbit

  • New Features

    • Imported URDF joint effort limits are now captured and applied to revolute and prismatic joints.
  • Tests

    • Updated tests to verify imported joint effort limits are recorded.
  • Examples

    • Tightened particle-ground clearance check in an example to reduce tolerated penetration.
  • Chores

    • Updated changelog to document the new effort-limit handling.

…eation plumbing using the updated effort_limit

Signed-off-by: Kezhuo Wang <shuibianwang@gmail.com>
@kwang-12 kwang-12 temporarily deployed to external-pr-approval March 27, 2026 10:37 — with GitHub Actions Inactive
@coderabbitai
Copy link
Copy Markdown
Contributor

coderabbitai bot commented Mar 27, 2026

No actionable comments were generated in the recent review. 🎉

ℹ️ Recent review info
⚙️ Run configuration

Configuration used: Path: .coderabbit.yml

Review profile: CHILL

Plan: Pro

Run ID: c9cd1f1a-8f33-4457-ba69-8a4102dd854d

📥 Commits

Reviewing files that changed from the base of the PR and between 6530686 and 800c672.

📒 Files selected for processing (1)
  • newton/examples/mpm/example_mpm_anymal.py

📝 Walkthrough

Walkthrough

Reads URDF joint limit effort="..." (or builder default) and propagates it into created revolute/prismatic joints' effort_limit; includes changelog entry and a test asserting the parsed effort value.

Changes

Cohort / File(s) Summary
Changelog
CHANGELOG.md
Added Unreleased entry documenting URDF effort limit parsing and propagation.
URDF Import Implementation
newton/_src/utils/import_urdf.py
parse_urdf now uses builder.default_joint_cfg.effort_limit as a default, stores limit_effort on per-joint data (from default or <limit effort="...">), and forwards effort_limit to builder.add_joint_revolute(...) and builder.add_joint_prismatic(...).
Tests
newton/tests/test_import_urdf.py
Updated inline URDF in test_revolute_joint_urdf to include effort="6.78" and added an assertion that builder.joint_effort_limit[-1] contains 6.78.
Example
newton/examples/mpm/example_mpm_anymal.py
Tightened particle-ground clearance check from q[2] > -voxel_size to q[2] > -1.1 * voxel_size in test_final.

Sequence Diagram(s)

sequenceDiagram
    participant URDF as URDF file
    participant Parser as URDFParser
    participant Builder as Builder
    participant Joint as JointFactory

    URDF->>Parser: read <joint> and <limit effort="...">
    Parser->>Parser: set joint_data.limit_effort (explicit or default)
    Parser->>Builder: add_joint_*(..., effort_limit=joint_data.limit_effort)
    Builder->>Joint: construct revolute/prismatic with effort_limit
    Joint-->>Builder: created joint (with effort_limit)
Loading

Estimated code review effort

🎯 3 (Moderate) | ⏱️ ~20 minutes

Possibly related PRs

Suggested reviewers

  • eric-heiden
  • vreutskyy
🚥 Pre-merge checks | ✅ 2 | ❌ 1

❌ Failed checks (1 warning)

Check name Status Explanation Resolution
Docstring Coverage ⚠️ Warning Docstring coverage is 33.33% which is insufficient. The required threshold is 80.00%. Write docstrings for the functions missing them to satisfy the coverage threshold.
✅ Passed checks (2 passed)
Check name Status Explanation
Description Check ✅ Passed Check skipped - CodeRabbit’s high-level summary is enabled.
Title check ✅ Passed The title accurately summarizes the main change: adding joint effort limit parsing in URDF imports, which is the primary focus across all modified files.

✏️ Tip: You can configure your own custom pre-merge checks in the settings.

✨ Finishing Touches
🧪 Generate unit tests (beta)
  • Create PR with unit tests

Thanks for using CodeRabbit! It's free for OSS, and your support helps us grow. If you like it, consider giving us a shout-out.

❤️ Share

Comment @coderabbitai help to get the list of available commands and usage tips.

@kwang-12 kwang-12 temporarily deployed to external-pr-approval March 27, 2026 10:37 — with GitHub Actions Inactive
Copy link
Copy Markdown
Contributor

@coderabbitai coderabbitai bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🧹 Nitpick comments (1)
newton/_src/utils/import_urdf.py (1)

803-821: Consider propagating effort limit to planar joints.

The planar joint type constructs JointDofConfig objects but doesn't pass the URDF-parsed effort_limit. This means planar joints will use the JointDofConfig default (1e6) instead of any URDF-specified value.

This is likely acceptable since planar joints are uncommon and the PR scope focuses on revolute/prismatic, but could be addressed for completeness.

♻️ Optional: propagate effort_limit to planar JointDofConfig
 created_joint_idx = builder.add_joint_d6(
     linear_axes=[
         ModelBuilder.JointDofConfig(
             u,
             limit_lower=lower * scale,
             limit_upper=upper * scale,
             target_kd=joint_damping,
             actuator_mode=actuator_mode,
+            effort_limit=effort_limit if effort_limit is not None else builder.default_joint_cfg.effort_limit,
         ),
         ModelBuilder.JointDofConfig(
             v,
             limit_lower=lower * scale,
             limit_upper=upper * scale,
             target_kd=joint_damping,
             actuator_mode=actuator_mode,
+            effort_limit=effort_limit if effort_limit is not None else builder.default_joint_cfg.effort_limit,
         ),
     ],
     **joint_params,
 )
🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@newton/_src/utils/import_urdf.py` around lines 803 - 821, The planar joint
creation currently builds two ModelBuilder.JointDofConfig entries without
passing the URDF-parsed effort_limit, causing the defaults to be used; update
the builder.add_joint_d6 call (and the two ModelBuilder.JointDofConfig
constructors for u and v) to include effort_limit=<effort_limit_variable> (or
effort_limit * scale if efforts are scaled) so the URDF effort limit is
propagated to both DOFs when creating created_joint_idx.
🤖 Prompt for all review comments with AI agents
Verify each finding against the current code and only fix it if needed.

Nitpick comments:
In `@newton/_src/utils/import_urdf.py`:
- Around line 803-821: The planar joint creation currently builds two
ModelBuilder.JointDofConfig entries without passing the URDF-parsed
effort_limit, causing the defaults to be used; update the builder.add_joint_d6
call (and the two ModelBuilder.JointDofConfig constructors for u and v) to
include effort_limit=<effort_limit_variable> (or effort_limit * scale if efforts
are scaled) so the URDF effort limit is propagated to both DOFs when creating
created_joint_idx.

ℹ️ Review info
⚙️ Run configuration

Configuration used: Path: .coderabbit.yml

Review profile: CHILL

Plan: Pro

Run ID: 916350a8-9cee-49fb-bad7-654754e737ea

📥 Commits

Reviewing files that changed from the base of the PR and between 8402740 and 20fea82.

📒 Files selected for processing (3)
  • CHANGELOG.md
  • newton/_src/utils/import_urdf.py
  • newton/tests/test_import_urdf.py

@codecov
Copy link
Copy Markdown

codecov bot commented Mar 27, 2026

Codecov Report

✅ All modified and coverable lines are covered by tests.
✅ All tests successful. No failed tests found.

📢 Thoughts on this report? Let us know!

eric-heiden
eric-heiden previously approved these changes Mar 30, 2026
Copy link
Copy Markdown
Member

@eric-heiden eric-heiden left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks!

@eric-heiden eric-heiden enabled auto-merge March 30, 2026 07:24
@dsmither-lgtm dsmither-lgtm added this to the 1.1 Release milestone Mar 30, 2026
@kwang-12 kwang-12 temporarily deployed to external-pr-approval March 31, 2026 15:36 — with GitHub Actions Inactive
@kwang-12 kwang-12 temporarily deployed to external-pr-approval April 1, 2026 12:36 — with GitHub Actions Inactive
@kwang-12 kwang-12 temporarily deployed to external-pr-approval April 1, 2026 19:39 — with GitHub Actions Inactive
@kwang-12 kwang-12 temporarily deployed to external-pr-approval April 1, 2026 22:48 — with GitHub Actions Inactive
@kwang-12 kwang-12 temporarily deployed to external-pr-approval April 1, 2026 22:48 — with GitHub Actions Inactive
Copy link
Copy Markdown
Contributor

@coderabbitai coderabbitai bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🧹 Nitpick comments (1)
newton/_src/utils/import_urdf.py (1)

803-821: Consider propagating effort_limit to planar joints for consistency.

The JointDofConfig instances for planar joints are constructed without effort_limit, causing them to use the class default (1e6) rather than the URDF-specified or builder-default value. For consistency with revolute/prismatic handling, consider passing the effort limit here as well.

♻️ Suggested fix
             created_joint_idx = builder.add_joint_d6(
                 linear_axes=[
                     ModelBuilder.JointDofConfig(
                         u,
                         limit_lower=lower * scale,
                         limit_upper=upper * scale,
                         target_kd=joint_damping,
                         actuator_mode=actuator_mode,
+                        effort_limit=effort_limit if effort_limit is not None else default_joint_limit_effort,
                     ),
                     ModelBuilder.JointDofConfig(
                         v,
                         limit_lower=lower * scale,
                         limit_upper=upper * scale,
                         target_kd=joint_damping,
                         actuator_mode=actuator_mode,
+                        effort_limit=effort_limit if effort_limit is not None else default_joint_limit_effort,
                     ),
                 ],
                 **joint_params,
             )
🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@newton/_src/utils/import_urdf.py` around lines 803 - 821, The planar joint D6
DOF configs omit the effort limit, so update the two ModelBuilder.JointDofConfig
calls inside builder.add_joint_d6 to include the URDF/builder effort value
(e.g., effort_limit) so they don't fall back to the 1e6 default; add
effort_limit=effort_limit (or effort_limit * scale if your units require
scaling) alongside limit_lower, limit_upper, target_kd=joint_damping, and
actuator_mode to both DOF configs.
🤖 Prompt for all review comments with AI agents
Verify each finding against the current code and only fix it if needed.

Nitpick comments:
In `@newton/_src/utils/import_urdf.py`:
- Around line 803-821: The planar joint D6 DOF configs omit the effort limit, so
update the two ModelBuilder.JointDofConfig calls inside builder.add_joint_d6 to
include the URDF/builder effort value (e.g., effort_limit) so they don't fall
back to the 1e6 default; add effort_limit=effort_limit (or effort_limit * scale
if your units require scaling) alongside limit_lower, limit_upper,
target_kd=joint_damping, and actuator_mode to both DOF configs.

ℹ️ Review info
⚙️ Run configuration

Configuration used: Path: .coderabbit.yml

Review profile: CHILL

Plan: Pro

Run ID: 0f67a978-d3f5-4794-9521-f3787da69877

📥 Commits

Reviewing files that changed from the base of the PR and between 20fea82 and 7d8bdbe.

📒 Files selected for processing (3)
  • CHANGELOG.md
  • newton/_src/utils/import_urdf.py
  • newton/tests/test_import_urdf.py
✅ Files skipped from review due to trivial changes (1)
  • CHANGELOG.md
🚧 Files skipped from review as they are similar to previous changes (1)
  • newton/tests/test_import_urdf.py

@adenzler-nvidia
Copy link
Copy Markdown
Member

@kwang-12 could you please have a look at the failing test? It looks ok visually, likely just an issue with the timing of the check. But it looks like a deterministic failure.

@kwang-12 kwang-12 had a problem deploying to external-pr-approval April 3, 2026 22:54 — with GitHub Actions Error
@kwang-12 kwang-12 had a problem deploying to external-pr-approval April 3, 2026 22:54 — with GitHub Actions Error
auto-merge was automatically disabled April 4, 2026 01:14

Head branch was pushed to by a user without write access

@kwang-12 kwang-12 temporarily deployed to external-pr-approval April 4, 2026 01:14 — with GitHub Actions Inactive
@kwang-12
Copy link
Copy Markdown
Contributor Author

kwang-12 commented Apr 4, 2026

@adenzler-nvidia I have investigated the issue and it turns out clamping joint effort limit for this particular test caused the particle to penetrate the ground slightly more than the old threshold at #line299
Debug prints shows that

ValueError: Test "all particles are above the ground" failed for 4 out of 486416 particles: [365458 (q=[-0.3357261   1.7689394  -0.03177082]), 365474 (q=[-0.3358123   1.7668804  -0.03293435]), 367089 (q=[-0.33848035  1.7811882  -0.03139702]), 367090 (q=[-0.33415273  1.7755159  -0.03251975])]

The example was ran with default voxel size of 0.03 so the violation is basically harmless. The debug print also shows the failed particles are clustered close to each other.

In 800c672, I have relaxed the test_particle_state threshold in example_mpm_anymal from lambda q, qd: q[2] > -voxel_size, to lambda q, qd: q[2] > -1.1 * voxel_size,
This resolves the issue cleanly.
All tests ran without problem on my machine with command:
uv run -m newton.examples.mpm.example_mpm_anymal --test --viewer null --num-frames 100
and
uv run --extra dev --extra torch-cu13 -m newton.tests --no-cache-clear --junit-report-xml rspec.xml --coverage --coverage-xml coverage.xml

@eric-heiden eric-heiden added this pull request to the merge queue Apr 7, 2026
Merged via the queue into newton-physics:main with commit e7b5d8c Apr 7, 2026
25 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants