Skip to content

[JTC] Add goal_timeout parameter to abort action when total trajectory time exceeds limit#2360

Open
kamal2730 wants to merge 7 commits into
ros-controls:masterfrom
kamal2730:feat/add_goal_timeout
Open

[JTC] Add goal_timeout parameter to abort action when total trajectory time exceeds limit#2360
kamal2730 wants to merge 7 commits into
ros-controls:masterfrom
kamal2730:feat/add_goal_timeout

Conversation

@kamal2730

@kamal2730 kamal2730 commented May 16, 2026

Copy link
Copy Markdown
Contributor

Description

Implements a goal_timeout parameter for joint_trajectory_controller that addresses issue #548: when goal_time_tolerance = 0.0 and the goal position cannot be reached, the action never returns a result and hangs indefinitely.

What it does

  • Adds goal_timeout (double, default 0.0 = disabled)
  • When set > 0.0, the action is aborted with GOAL_TOLERANCE_VIOLATED if total elapsed time from trajectory start exceeds the timeout
  • The check is placed after all tolerance checks and action feedback processing, so it cannot be overridden by state tolerance or goal tolerance transitions
  • Includes validation: warns when goal_timeout < constraints.goal_time
  • Both action-level and controller-level tests added

Fixes #548

Is this user-facing behavior change?

Did you use Generative AI?

NO

Additional Information

TODOs

To send us a pull request, please:

  • Fork the repository.
  • Modify the source; please focus on the specific change you are contributing. If you also reformat all the code, it will be hard for us to focus on your change.
  • Ensure local tests pass. (colcon test and pre-commit run (requires you to install pre-commit by pip3 install pre-commit)
  • Commit to your fork using clear commit messages.
  • Send a pull request, answering any default questions in the pull request interface.
  • Pay attention to any automated CI failures reported in the pull request, and stay involved in the conversation.

@kamal2730

Copy link
Copy Markdown
Contributor Author

Hello @christophfroehlich , this PR is ready for review. Kindly review it when you have time.

@bmagyar bmagyar requested a review from MarqRazz May 21, 2026 06:10

@MarqRazz MarqRazz left a comment

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

What happens when a user specifies it in the goal request and it started disabled? Will that enable it with those settings from that point on? (Like a parameter change would)

# If the joints are not within goal_tolerance after "trajectory finish
# time" + goal_time_tolerance, the goal aborts with error_code set to
# GOAL_TOLERANCE_VIOLATED
JointTolerance[] goal_tolerance
JointComponentTolerance[] component_goal_tolerance
builtin_interfaces/Duration goal_time_tolerance

Comment thread joint_trajectory_controller/src/joint_trajectory_controller.cpp Outdated
@MarqRazz

MarqRazz commented Jun 1, 2026

Copy link
Copy Markdown
Contributor

Can you detail better how this is different than the constraints:goal_time parameter? I've used that and it works as expected. The only thing I don't like about it is that you can't make it a function of the trajectory sent (its just a fixed number). I would like functionality like MoveIt where it does commanded trajectory + percentage. So you can say goal_time=1.3 and that would add a 30% time buffer.

@kamal2730

Copy link
Copy Markdown
Contributor Author

Hello @MarqRazz , Thanks for the review

What happens when a user specifies it in the goal request and it started disabled? Will that enable it with those settings from that point on? (Like a parameter change would)

# If the joints are not within goal_tolerance after "trajectory finish
# time" + goal_time_tolerance, the goal aborts with error_code set to
# GOAL_TOLERANCE_VIOLATED
JointTolerance[] goal_tolerance
JointComponentTolerance[] component_goal_tolerance
builtin_interfaces/Duration goal_time_tolerance

The goal_timeout parameter is independent from the action goal's goal_time_tolerance field. Setting goal_time_tolerance in the goal request has no effect on goal_timeout .

Can you detail better how this is different than the constraints:goal_time parameter? I've used that and it works as expected. The only thing I don't like about it is that you can't make it a function of the trajectory sent (its just a fixed number). I would like functionality like MoveIt where it does commanded trajectory + percentage. So you can say goal_time=1.3 and that would add a 30% time buffer.

  • constraints.goal_time is a grace period that starts after the trajectory's last point , it only fires when you've reached the end and the robot hasn't settled into goal tolerances.
  • goal_timeout is an absolute wall-clock deadline measured from trajectory start ,it applies even mid-trajectory, acting as a hard cap.

@kamal2730 kamal2730 requested a review from MarqRazz June 4, 2026 10:14

@MarqRazz MarqRazz left a comment

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Thanks for taking the time to describe the difference!

Do you think this new parameter should be part of the constraints namespace?

Comment thread joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml Outdated
Comment thread joint_trajectory_controller/src/joint_trajectory_controller.cpp Outdated
Comment thread joint_trajectory_controller/src/joint_trajectory_controller.cpp Outdated
@kamal2730

Copy link
Copy Markdown
Contributor Author

Thanks for taking the time to describe the difference!

Do you think this new parameter should be part of the constraints namespace?

I think keeping it top-level makes more sense for consistency , cmd_timeout is also a timeout and lives at the top level, not under constraints. The constraints namespace is primarily for per-joint tolerances (trajectory, goal, max_deceleration) plus goal_time and stopped_velocity_tolerance, which are all about checking deviation between desired and actual state. goal_timeout is a different concept , it's a hard execution deadline, not a tolerance check. So constraints would be a bit misleading.

@kamal2730 kamal2730 requested a review from MarqRazz June 5, 2026 03:29
MarqRazz
MarqRazz previously approved these changes Jun 5, 2026

@MarqRazz MarqRazz left a comment

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

The code changes look good, thanks for adjusting it to tell the user what is happening!

Comment thread joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml Outdated

@christophfroehlich christophfroehlich 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.

Main changes LGTM, one thing: please add a note here.

@codecov

codecov Bot commented Jun 6, 2026

Copy link
Copy Markdown

Codecov Report

❌ Patch coverage is 91.93548% with 5 lines in your changes missing coverage. Please review.
✅ Project coverage is 85.64%. Comparing base (68630ae) to head (081c0aa).

Files with missing lines Patch % Lines
...ory_controller/src/joint_trajectory_controller.cpp 78.26% 3 Missing and 2 partials ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##           master    #2360      +/-   ##
==========================================
+ Coverage   85.61%   85.64%   +0.02%     
==========================================
  Files         148      148              
  Lines       15837    15899      +62     
  Branches     1339     1344       +5     
==========================================
+ Hits        13559    13616      +57     
- Misses       1792     1795       +3     
- Partials      486      488       +2     
Flag Coverage Δ
unittests 85.64% <91.93%> (+0.02%) ⬆️

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

Files with missing lines Coverage Δ
...jectory_controller/joint_trajectory_controller.hpp 40.00% <ø> (ø)
...ectory_controller/test/test_trajectory_actions.cpp 97.70% <100.00%> (+0.07%) ⬆️
...ory_controller/test/test_trajectory_controller.cpp 99.35% <100.00%> (+<0.01%) ⬆️
...ory_controller/src/joint_trajectory_controller.cpp 83.83% <78.26%> (-0.15%) ⬇️
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

@kamal2730

Copy link
Copy Markdown
Contributor Author

@christophfroehlich Added release notes. Could you please review?

@saikishor saikishor 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.

@kamal2730 @christophfroehlich if the goal_time_tolerance is zero, and then if the position is not reached within the duration specified in the goal or the published message. Then, it should abort immediately after the time is passed right?. Do we really need a parameter here? Or Am i missing something?

@christophfroehlich

Copy link
Copy Markdown
Member

problem is that with goal_time being zero that the action never gets cancelled. at least this is what I understood from the issue.

@saikishor

Copy link
Copy Markdown
Member

problem is that with goal_time being zero that the action never gets cancelled. at least this is what I understood from the issue.

Yes me too, that's what I understood, but then it is a bug. I would solve it properly instead of adding yet another new parameters

@kamal2730

Copy link
Copy Markdown
Contributor Author

@kamal2730 @christophfroehlich if the goal_time_tolerance is zero, and then if the position is not reached within the duration specified in the goal or the published message. Then, it should abort immediately after the time is passed right?. Do we really need a parameter here? Or Am i missing something?

Hello @saikishor,

Thanks for the review.

You're right - fixing the != 0.0 guard so that goal_time_tolerance = 0 means "abort immediately at trajectory end" would solve the hanging issue entirely. The combination of time_from_start (planned duration) and goal_time_tolerance (grace period) already covers both cases: aborting immediately at the end of the trajectory or allowing additional settling time.

However, the current documented and intended behavior of goal_time = 0 is: "If set to zero, the controller will wait a potentially infinite amount of time." Some users may explicitly rely on this behavior because the action is considered complete only after all joints satisfy their configured goal tolerances, regardless of how long that takes. Changing the semantics of goal_time = 0 would therefore be a breaking change for anyone who expects the controller to keep waiting until the goal tolerances are met.

That's the main reason I chose to introduce a new parameter rather than change the existing behavior.

That said, if the maintainers are comfortable with the breaking change, I'm happy to take that approach instead.

@kamal2730 kamal2730 requested a review from saikishor June 8, 2026 03:35
@saikishor

Copy link
Copy Markdown
Member

However, the current documented and intended behavior of goal_time = 0 is: "If set to zero, the controller will wait a potentially infinite amount of time." Some users may explicitly rely on this behavior because the action is considered complete only after all joints satisfy their configured goal tolerances, regardless of how long that takes. Changing the semantics of goal_time = 0 would therefore be a breaking change for anyone who expects the controller to keep waiting until the goal tolerances are met.

I don't think waiting an infinite amount of time is the right approach. I don't think we should allow it. For the action, the user will have to cancel it himself right?

@kamal2730

Copy link
Copy Markdown
Contributor Author

I don't think waiting an infinite amount of time is the right approach. I don't think we should allow it. For the action, the user will have to cancel it himself right?

Yes, you are correct. However, goal_time = 0 does not always cause an infinite wait. It only does so in the specific case where the robot can never satisfy the goal tolerances (for example, due to mechanical constraints).

In most real-world scenarios, the robot simply needs a little more time to settle. Maybe the motor is slightly slower than expected, or there is some friction, and the robot will eventually reach the goal if given additional time. That's the normal case, and I believe this is the reason the current behavior was intentionally designed this way.

If we change goal_time = 0 to abort immediately at the end of the trajectory, we would break those normal cases. The action would fail even though the robot was about to reach the goal. The current behavior, which is to wait as long as necessary for the goal tolerances to be satisfied, is beneficial for these situations.

The real problem is the edge case where the robot can never reach the goal or satisfy the goal tolerances. That's where the new action_execution_timeout parameter helps. It provides a hard safety limit without changing the existing behavior that many users may rely on.

@christophfroehlich

Copy link
Copy Markdown
Member

I'm fine with both approaches. We can't just break current behavior on distros other than rolling. so maybe we merge this only in distros from jazzy backwards

@github-project-automation github-project-automation Bot moved this from Needs discussion to WIP in Review triage Jun 8, 2026
@christophfroehlich christophfroehlich moved this to Needs discussion in Review triage Jun 8, 2026
@christophfroehlich christophfroehlich moved this from WIP to Needs discussion in Review triage Jun 10, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

Status: Needs discussion

Development

Successfully merging this pull request may close these issues.

JTC action result never returns

4 participants