Skip to content

Add set_target_payload support to ScriptCommandInterface#515

Merged
urfeex merged 10 commits into
UniversalRobots:masterfrom
srvald:set_target_payload
Jun 17, 2026
Merged

Add set_target_payload support to ScriptCommandInterface#515
urfeex merged 10 commits into
UniversalRobots:masterfrom
srvald:set_target_payload

Conversation

@srvald

@srvald srvald commented Jun 5, 2026

Copy link
Copy Markdown
Contributor

Description

Adds support for the URScript set_target_payload() command through the
ScriptCommandInterface, allowing users to set the payload mass, center of
gravity, inertia matrix, and transition time.

This follows the same pattern as the existing setPayload() implementation.

Changes

  • include/ur_client_library/control/script_command_interface.h: Added
    setTargetPayload() declaration and the SET_TARGET_PAYLOAD = 12 enum value
    to ScriptCommand.
  • include/ur_client_library/ur/ur_driver.h: Added setTargetPayload()
    declaration to UrDriver.
  • src/control/script_command_interface.cpp: Implemented
    ScriptCommandInterface::setTargetPayload(), encoding mass, CoG (3 values),
    inertia matrix (6 values), and transition time into the binary message.
  • src/ur/ur_driver.cpp: Implemented UrDriver::setTargetPayload().
  • resources/external_control.urscript: Added SET_TARGET_PAYLOAD = 12
    constant and the corresponding elif branch in the script_commands thread
    to call set_target_payload().
  • tests/test_script_command_interface.cpp: Added
    test_set_target_payload unit test verifying correct encoding of all fields
    (mass, CoG, inertia, transition time) and that unused message slots are zero.

Message layout for SET_TARGET_PAYLOAD

Index Meaning
0 Command (12)
1 Mass (kg)
2–4 Center of gravity (m)
5–10 Inertia matrix elements (kg·m²)
11 Transition time (s)
12–27 Unused (zero-padded)

Notes

  • transition_time defaults to 0.0 seconds (no transition).

Related issues

UniversalRobots/Universal_Robots_ROS2_Driver#1711

Related PR (ur_ros2_driver): UniversalRobots/Universal_Robots_ROS2_Driver#1808

Tasks

  • Implement the feature
  • Make documentation
  • Make Unit test
  • Make example
  • Test on real hardware

Note

Medium Risk
Changes active payload modeling on the robot (mass, inertia, timed transitions), which affects motion and force behavior; version fallbacks limit inertia on older PolyScope but mass/CoG still apply.

Overview
Adds setTargetPayload() on UrDriver and ScriptCommandInterface, exposing URScript set_target_payload() (mass, CoG, inertia, transition time) over the existing script-command socket as command 12 (SET_TARGET_PAYLOAD), mirroring setPayload().

The binary path encodes eleven payload fields plus transition time (MULT_JOINTSTATE / MULT_TIME); external_control.urscript decodes them and calls set_target_payload() on PolyScope ≥ 5.10, otherwise falls back to set_payload() and logs that inertia and transition time are ignored. MULT_TIME is moved to ReverseInterface (removed from TrajectoryPointInterface).

Docs, the script-command example, and unit/integration tests cover encoding and driver behavior (connected interface and plain-script fallback).

Reviewed by Cursor Bugbot for commit a86f7b3. Bugbot is set up for automated code reviews on this repo. Configure here.

@codecov

codecov Bot commented Jun 5, 2026

Copy link
Copy Markdown

Codecov Report

❌ Patch coverage is 97.36842% with 1 line in your changes missing coverage. Please review.
✅ Project coverage is 78.90%. Comparing base (915eafe) to head (a86f7b3).
⚠️ Report is 2 commits behind head on master.

Files with missing lines Patch % Lines
src/ur/ur_driver.cpp 94.11% 0 Missing and 1 partial ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##           master     #515      +/-   ##
==========================================
- Coverage   78.95%   78.90%   -0.05%     
==========================================
  Files         116      115       -1     
  Lines        6689     6764      +75     
  Branches     2953     2986      +33     
==========================================
+ Hits         5281     5337      +56     
- Misses       1040     1055      +15     
- Partials      368      372       +4     
Flag Coverage Δ
check_version_ur10-3.15.8 12.56% <0.00%> (+0.41%) ⬆️
check_version_ur10e-10.11.0 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur10e-5.15.2 11.30% <0.00%> (+<0.01%) ⬆️
check_version_ur12e-10.12.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur12e-5.25.1 11.11% <0.00%> (-0.33%) ⬇️
check_version_ur15-10.12.1 11.16% <0.00%> (-0.09%) ⬇️
check_version_ur15-5.25.1 11.16% <0.00%> (-0.50%) ⬇️
check_version_ur16e-10.12.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur16e-5.25.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur18-10.12.1 11.11% <0.00%> (-0.19%) ⬇️
check_version_ur18-5.25.1 11.73% <0.00%> (+0.29%) ⬆️
check_version_ur20-10.12.1 11.11% <0.00%> (-0.19%) ⬇️
check_version_ur20-5.25.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur3-3.14.3 11.52% <0.00%> (+0.08%) ⬆️
check_version_ur30-10.12.1 11.11% <0.00%> (-0.24%) ⬇️
check_version_ur30-5.25.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur3e-10.11.0 11.11% <0.00%> (-0.24%) ⬇️
check_version_ur3e-5.9.4 11.11% <0.00%> (-0.33%) ⬇️
check_version_ur5-3.15.8 11.34% <0.00%> (+0.01%) ⬆️
check_version_ur5e-10.11.0 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur5e-5.12.8 11.34% <0.00%> (+<0.01%) ⬆️
check_version_ur7e-10.11.0 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur7e-5.22.2 11.30% <0.00%> (+0.05%) ⬆️
check_version_ur8long-10.12.1 11.11% <0.00%> (-0.14%) ⬇️
check_version_ur8long-5.25.1 11.11% <0.00%> (-0.33%) ⬇️
python_scripts 75.90% <ø> (ø)
start_ursim 84.00% <ø> (-0.48%) ⬇️
ur5-3.14.3 74.52% <84.21%> (-0.20%) ⬇️
ur5e-10.11.0 69.31% <86.84%> (+0.18%) ⬆️
ur5e-10.12.0 70.21% <86.84%> (-0.01%) ⬇️
ur5e-10.7.0 68.65% <86.84%> (-0.27%) ⬇️
ur5e-5.9.4 75.11% <84.21%> (-0.24%) ⬇️

Flags with carried forward coverage won't be shown. Click here to find out more.

☔ View full report in Codecov by Harness.
📢 Have feedback on the report? Share it here.

@urfeex urfeex force-pushed the set_target_payload branch from 67d123d to 2d1074a Compare June 8, 2026 07:29
Comment thread resources/external_control.urscript Outdated
Comment thread src/ur/ur_driver.cpp

@urfeex urfeex left a comment

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

This is looking clean! I'm only wondering whether we should move the MULT_TIME up to ReverseInterface and re-use that for the transition time. I think, we should do that.

Comment thread resources/external_control.urscript Outdated
Comment thread src/control/script_command_interface.cpp Outdated
Comment thread tests/test_script_command_interface.cpp Outdated
@srvald srvald requested a review from urfeex June 10, 2026 08:06

@urfeex urfeex left a comment

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Please also add documentation updates to script_command_interface.rst and add a command to the script_command_example,

@srvald srvald requested a review from urfeex June 10, 2026 08:55
@srvald

srvald commented Jun 10, 2026

Copy link
Copy Markdown
Contributor Author

@urfeex Should we put somewhere that setPayload is deprecated?

@urfeex

urfeex commented Jun 10, 2026

Copy link
Copy Markdown
Member

@urfeex Should we put somewhere that setPayload is deprecated?

I would say let's not add a compile time deprecation. We could print a warning when setPayload is used on a robot with software newer than or equal to 5.10/3.15 (which covers most of our supported versions, anyway). @urrsk what is your opinion on this?

@cursor cursor Bot left a comment

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Cursor Bugbot has reviewed your changes using default effort and found 1 potential issue.

Fix All in Cursor

Reviewed by Cursor Bugbot for commit e067c0c. Configure here.

{% else %}
set_payload(mass, cog)
textmsg("PolyScope < 5.10.0. Inertia and transition_time ignored.")
{% endif %}

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Missing PolyScope 3.15 gate

Medium Severity

set_target_payload availability is gated only on PolyScope 5.10+, but the API was also introduced in PolyScope 3.15. On 3.15+ CB3 robots, the script and fallback paths call set_payload instead, so inertia and transition_time from setTargetPayload are dropped while the call still succeeds.

Additional Locations (1)
Fix in Cursor Fix in Web

Reviewed by Cursor Bugbot for commit e067c0c. Configure here.

urfeex added 2 commits June 17, 2026 12:24
Otherwise this will affect other tests running on the same robot later.
@urfeex urfeex added the enhancement New feature or request label Jun 17, 2026
@urfeex urfeex merged commit 03a62bd into UniversalRobots:master Jun 17, 2026
54 of 63 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

enhancement New feature or request

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants