-
Notifications
You must be signed in to change notification settings - Fork 21
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
persistent "Final position was outside tolerance" #233
Comments
Could you please provide:
(if easier: a minimal action client which submits a goal which results in the problem you report would also be ok -- and would make it easier to reproduce your problem) Edit: and ideally: a Wireshark capture of the network traffic between your Agent and MotoROS2. |
I've edited the title of the issue to better reflect the symptoms observed. We can't conclude yet what is the cause. |
I just noticed the motoros2/src/ActionServer_FJT.c Lines 505 to 507 in d563a79
I'm wondering if We should probably be using this value for the comparison instead: Lines 24 to 25 in d563a79
|
I've seen infinitesimal values for fields which were supposed to be It's possible the (de)serialisation causes the field to no longer be exactly |
Although thinking about it more: I'm curious to understand what makes this come up now in these cases, as the code implicated hasn't seen changes since MotoROS2 was first released. |
Here are the requested files: |
As @yai-rosejo noted in #235 (comment), the The trajectory shared by @Illumo-Vincent (@rsaintobert?) has this: path_tolerance: []
component_path_tolerance: []
goal_tolerance: []
component_goal_tolerance: [] without a check here on the length of the array: motoros2/src/ActionServer_FJT.c Lines 505 to 507 in d563a79
we're most likely indexing into uninitialised memory. This is UB in any case, but for some reason tends to fail for @rsaintobert / @Illumo-Vincent (and @TE-2 in #235) more than for other users, leading to the issue reported. The change made by @ted-miller in #236 is a good one, but if we're indeed not sufficiently checking for Edit: I've tried reproducing the issue with MoveIt, but don't seem to be able to. That doesn't mean it doesn't exist. I might just 'be lucky' and the memory being read happens to evaluate to a larger |
Looking into this more, it seems the current code doesn't parse the motoros2/src/ActionServer_FJT.c Line 505 in d563a79
It assumes all joints have a tolerance provided and the elements are ordered in the same way as the joints in the In reality, we can't assume @ted-miller: my suggestion would be to disable the final We have to keep in mind that in almost all cases, the Yaskawa controller will already have aborted the motion in case tracking error prevents it from faithfully executing the trajectory. The additional |
Always use the hard-coded default position tolerance. See #233.
This comment was marked as outdated.
This comment was marked as outdated.
@yai-rosejo has a fix which he's validating now. |
I have been working on a potential fix which can be found on my branch here: To run these tests:
|
It seems we're fighting multiple issues.
A brief test indicated that the fb pos trails the cmd pos by about .0009 radians. If my calculations are right, for some axes (such as GP12 T axis) that's only 24 pulse counts. So, once the increment-queue is empty, I'm also suspicious that the difference between fb and cmd could shrink as the robot is decelerating. This might make it easier for other axes to also exceed the threshold.
More testing is needed before we'll have an idea for PR. |
Could we open and merge PRs for each of the identified issues? The fix for the incorrect parsing of the tolerances by @yai-rosejo seems like a good first step. Regardless of whether any of the other issues get fixed, loading those tolerance entries would need to be corrected. |
@rsaintobert: with the merge of #241 this should now be fixed. We'll have to release a new binary for this to be generally available though. Please let us know whether you'd like a prerelease build. |
Hello everyone, I’m encountering the same issue where the robot moves successfully to the first waypoint (in Cartesian space) using the MoveIt Task Constructor (MTC), but then the following error occurs: [move_group-4] [WARN] [1725660470.550437309] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Controller 'follow_joint_trajectory' failed with error: unknown error: Final position was outside tolerance. Check robot safety limits that could be inhibiting motion. [group_1/joint_5: 0.0000 deviation] After reaching the first waypoint, I think the error is stopping the entire process, preventing the robot from continuing through the remaining waypoints to generate a complete trajectory. Here are some relevant details:
What I’ve tried:
Here are my questions:
Any help would be greatly appreciated. Thank you, |
Anytime a trajectory is submitted I get the following error (with more or less joints incriminated), and the goal is aborted.
The log is done here but the 4-digits precision does not give enough info. Anyway the deviation is quite low here.
Click to expand:
motoros2/src/ActionServer_FJT.c
Lines 563 to 580 in 9026a1d
The problem is more in the check of the deviation:
Click to expand:
motoros2/src/ActionServer_FJT.c
Lines 500 to 520 in 9026a1d
Leaving the goal_tolerance parameter unset in the goal request should default to a tolerance of 0.01 which is not the case. Maybe the message buffer is badly initialized ?
Click to expand:
motoros2/src/ActionServer_FJT.c
Lines 511 to 512 in 9026a1d
Anyway, any value set in the goal request leads to the same result, so the user input is not taken properly into account.
The text was updated successfully, but these errors were encountered: