Skip to content
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

Require velocity and acceleration limits in TOTG #1794

Merged
merged 3 commits into from
Dec 20, 2022

Conversation

AndyZe
Copy link
Member

@AndyZe AndyZe commented Dec 8, 2022

This PR prints an error and returns false if vel/accel isn't defined for a robot joint, instead of assigning a default value and moving on.

Fixes #1793 and this UR issue: UniversalRobots/Universal_Robots_ROS2_Description#46

@codecov
Copy link

codecov bot commented Dec 8, 2022

Codecov Report

Base: 50.33% // Head: 50.30% // Decreases project coverage by -0.03% ⚠️

Coverage data is based on head (709c201) compared to base (43b06e9).
Patch coverage: 0.00% of modified lines in pull request are covered.

Additional details and impacted files
@@            Coverage Diff             @@
##             main    #1794      +/-   ##
==========================================
- Coverage   50.33%   50.30%   -0.02%     
==========================================
  Files         374      374              
  Lines       31325    31329       +4     
==========================================
- Hits        15763    15757       -6     
- Misses      15562    15572      +10     
Impacted Files Coverage Δ
...cessing/src/time_optimal_trajectory_generation.cpp 87.38% <0.00%> (-0.98%) ⬇️
moveit_core/utils/src/robot_model_test_utils.cpp 77.78% <ø> (ø)
...nning_scene_monitor/src/planning_scene_monitor.cpp 45.26% <0.00%> (-0.43%) ⬇️
...bot_model/include/moveit/robot_model/robot_model.h 90.75% <0.00%> (+0.36%) ⬆️
...bot_model/include/moveit/robot_model/joint_model.h 82.90% <0.00%> (+0.47%) ⬆️

Help us with your feedback. Take ten seconds to tell us how you rate us. Have a feature suggestion? Share it here.

☔ View full report at Codecov.
📢 Do you have feedback about the report comment? Let us know in this issue.

@AndyZe AndyZe force-pushed the andyz/require_all_limits branch 2 times, most recently from 49d6415 to 97d10c6 Compare December 8, 2022 21:37
@AndyZe AndyZe marked this pull request as draft December 9, 2022 01:45
@AndyZe AndyZe marked this pull request as ready for review December 9, 2022 05:42
@henningkayser
Copy link
Member

henningkayser commented Dec 9, 2022

Things like this make me wonder if we should always enforce having velocity and acceleration limits set at runtime. There is really no actual use case of MoveIt that makes sense without them, imo.

Opened up a discussion here: #1804

Copy link
Contributor

@sjahr sjahr left a comment

Choose a reason for hiding this comment

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

I think that change does make sense 👍 Here are a couple of comments

@AndyZe
Copy link
Member Author

AndyZe commented Dec 15, 2022

I think I'll just close this one because the discussion is tending toward requiring acceleration limits when the RobotModel is loaded.

@AndyZe AndyZe closed this Dec 15, 2022
@AndyZe
Copy link
Member Author

AndyZe commented Dec 20, 2022

Reviving this PR since the discussion about requiring accel limits seems to be a dead end.

@AndyZe AndyZe reopened this Dec 20, 2022
Co-authored-by: Sebastian Jahr <[email protected]>
@AndyZe AndyZe merged commit 937be8e into moveit:main Dec 20, 2022
@AndyZe AndyZe deleted the andyz/require_all_limits branch December 20, 2022 22:04
@v4hn
Copy link
Contributor

v4hn commented Dec 23, 2022

I'm surprised to see this change merged. Functionally the only thing it does is that you prohibit a use-case that did something intuitive but possibly sub-optimal before while printing an explicit warning. I don't see what the patch improves...

The least you should do is document migration notes telling users to explicitly add the default 1.0 rad/s^2 limits for all joints if they want it to work the way it did so far.
E.g., when controlling a robotiq 3-finger adaptive gripper, I am actually annoyed if I have to specify acceleration limits for each joint just to close the gripper. As pointed out in the linked UR issue, manufacturers do not provide that information.
Additionally, especially for beginners acceleration is completely irrelevant when they just want to move from A to B. I tend to explain the difference between perceived speed, velocity and acceleration quite some time after students set up their first configs and moved robots around via MoveIt.

@sjahr
Copy link
Contributor

sjahr commented Dec 23, 2022

Good point, that we should recommend 1.0 rad/s^2 as default for beginners 👍

I don't think that this patch prohibits a use-case but rather helps users to avoid an unexpected behavior of the robot moving very slow. Yes, a warning was printed but it was easy to overlook in the huge terminal output that MoveIt produces. As a user, I'd assume the acceleration limits to be treated as unlimited (which would prob. be an unsafe default value 😅 ), if I don't explicitly set them and not a magic number.

@v4hn
Copy link
Contributor

v4hn commented Dec 23, 2022 via email

@AndyZe
Copy link
Member Author

AndyZe commented Dec 23, 2022

Thinking along these lines, would it be a viable way around this whole discussion to add explicit defaults for velocity and acceleration to the joint_limits.yaml that apply whenever a joint does not define limits explicitly?

That seems like a good idea. The SRDF format doesn't even allow acceleration limits so we'd have to require a joint_limits.yaml

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.

If no acceleration limit is given in joint_limits.yaml or URDF, it defaults to 1.0 rad/s^2
4 participants