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

Add default velocity/acceleration scaling factors #1890

Merged
merged 14 commits into from
Mar 9, 2020

Conversation

felixvd
Copy link
Contributor

@felixvd felixvd commented Feb 12, 2020

Description

Since I was in the middle of touching adjacent code and @rhaschke mentioned (#1889) that he has no time to fully implement the feature, I quickly wrote this PR and it seems to work fine. As suggested in #1888 (@v4hn), this PR adds default velocity/acceleration scaling factors as ROS parameters to joint_limits.yaml so that the initial setting is 0.1 for each, which should ensure safer robot motions for beginners. The parameter is retrieved from the server when starting up a MoveGroup and when adding a MotionPlanning widget in Rviz.

It leaves the setting in the .ui file of the MotionPlanning widget somewhat redundant, but I guess it's not a big problem.

I would suggest adding a note to MIGRATION.md, throughout the tutorials, and maybe even somewhere else so that new users are aware that the robot is not moving at full speed.

Checklist

  • Required by CI: Code is auto formatted using clang-format
  • Extend the tutorials / documentation reference
  • Document API changes relevant to the user in the MIGRATION.md notes

Copy link
Contributor

@rhaschke rhaschke left a comment

Choose a reason for hiding this comment

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

Thanks for working on this! As you mentioned, the scaling factors should be limited to the range (0, 1]. Maybe, the Qt widget already handles that on the rviz side.
But, at least in the MoveGroupInterface you should add a corresponding clipping (and a warning).
My suggestion is:

  • value < 0 → use default
  • value > 1 → clip to 1.0

@felixvd
Copy link
Contributor Author

felixvd commented Feb 12, 2020

But, at least in the MoveGroupInterface you should add a corresponding clipping (and a warning).
My suggestion is:

  • value < 0 → use default
  • value > 1 → clip to 1.0

I didn't know that it wasn't already handled that way. I added the check as suggested.

@rhaschke
Copy link
Contributor

I didn't know that it wasn't already handled that way. I added the check as suggested.

Oh, I didn't check explicitly. Indeed, all the time parameterization methods to exactly the same checking (sorry for the noise!):
https://github.com/ros-planning/moveit/blob/6b56cd68d76ae29d1ceb255d06be35543dd3f830/moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp#L890-L905

... falling back to a default of 1.0.

I think this code should be refactored to have a common planning request adapt for time-parameterization, which in turn uses a specific time-parameterization plugin via a common interface.
The common planning request adapter would then be an ideal candidate to inject the default values, if they are still zero.
To keep things simple (and avoid code duplication), we could even hard-code the factors in rviz to 0.0.

@felixvd
Copy link
Contributor Author

felixvd commented Feb 13, 2020

Hmm, I would prefer to keep this PR small since the default parameters will be useful regardless, and it seems like a separate issue. Would you prefer to revert the clipping inside the MoveGroupInterface or keep it? I can see arguments for either.

Copy link
Contributor

@rhaschke rhaschke left a comment

Choose a reason for hiding this comment

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

I agree that this PR shouldn't be further extended. I pushed several cleanup commits.
@felixvd, please check again from your point of view.

@felixvd
Copy link
Contributor Author

felixvd commented Feb 13, 2020

Looks great, thanks! Agree with everything and only found that typo.

Co-Authored-By: Felix von Drigalski <FvDrigalski@gmail.com>
@rhaschke rhaschke added the awaits 2nd review one maintainer approved this request label Feb 13, 2020
@rhaschke
Copy link
Contributor

@v4hn, is this what you intended in #1888?

@codecov-io
Copy link

codecov-io commented Feb 13, 2020

Codecov Report

Merging #1890 into master will decrease coverage by 0.01%.
The diff coverage is 8.69%.

Impacted file tree graph

@@            Coverage Diff             @@
##           master    #1890      +/-   ##
==========================================
- Coverage   50.26%   50.25%   -0.02%     
==========================================
  Files         313      313              
  Lines       24623    24672      +49     
==========================================
+ Hits        12377    12398      +21     
- Misses      12246    12274      +28
Impacted Files Coverage Δ
...t_setup_assistant/src/tools/moveit_config_data.cpp 21.56% <0%> (-0.32%) ⬇️
.../move_group_interface/src/move_group_interface.cpp 22.53% <15.38%> (-0.25%) ⬇️
...xperimental/moveit_jog_arm/src/low_pass_filter.cpp 95.45% <0%> (-4.55%) ⬇️
...veit_experimental/moveit_jog_arm/src/jog_calcs.cpp 70.5% <0%> (-2.29%) ⬇️
...og_arm/include/moveit_jog_arm/jog_interface_base.h 100% <0%> (ø) ⬆️
...veit_jog_arm/include/moveit_jog_arm/jog_arm_data.h 100% <0%> (ø) ⬆️
moveit_core/planning_scene/src/planning_scene.cpp 46.13% <0%> (+0.14%) ⬆️
...erimental/moveit_jog_arm/src/jog_cpp_interface.cpp 12.04% <0%> (+0.14%) ⬆️
...erimental/moveit_jog_arm/src/jog_ros_interface.cpp 85.18% <0%> (+0.37%) ⬆️
...ccupancy_map_monitor/src/occupancy_map_monitor.cpp 30.61% <0%> (+0.95%) ⬆️
... and 2 more

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 6b56cd6...f8a26f8. Read the comment docs.

Copy link
Contributor

@v4hn v4hn left a comment

Choose a reason for hiding this comment

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

Thank you for proposing this @felixvd !

Assuming all the node handles are in the correct scope to see the parameters (didn't check),
this looks quite good!

Please have a look at the inline feedback.

Cartesian trajectory scaling remains an open issue for this approach to change defaults, because the current API does not care about the scaling factors. But I don't think this has to be dealt with here.

moveit_setup_assistant/src/tools/moveit_config_data.cpp Outdated Show resolved Hide resolved
else if (target <= 0.0)
{
node_handle_.param<double>(std::string("robot_description_planning/default_") + name, variable, fallback);
ROS_WARN_NAMED("move_group_interface", "max_%s <= 0.0! Setting to default: %.2f.", name, variable);
Copy link
Contributor

Choose a reason for hiding this comment

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

I would expect this to be reasonable behavior for this API, so I would prefer this as a ROS_DEBUG instead.

Copy link
Contributor

Choose a reason for hiding this comment

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

I don't agree. If the user specifies a negative scaling factor, she should get a warning about that.

Copy link
Contributor Author

@felixvd felixvd Feb 19, 2020

Choose a reason for hiding this comment

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

I agree that clipping the value to (0, 1] is reasonable behavior, but I think users should be alerted if they attempt to set it outside of that range.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Unrelated: shouldn't this be ROS_WARN_NAMED_STREAM?

Copy link
Contributor

Choose a reason for hiding this comment

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

Using stream syntax would be more verbose. But, I don't mind.

Copy link
Contributor

Choose a reason for hiding this comment

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

I don't agree. If the user specifies a negative scaling factor, she should get a warning about that.

If you insist, I can agree with the negative factor.
In this case, I would prefer to have a separate branch for 0.0 though.
Otherwise there is no warning-free API to reset the factors to their defaults (aside from the Constructor)!

node_handle_.param<double>("robot_description_planning/joint_limits/default_velocity_scaling_factor",
max_velocity_scaling_factor_, 0.1);
node_handle_.param<double>("robot_description_planning/joint_limits/default_acceleration_scaling_factor",
max_acceleration_scaling_factor_, 0.1);
Copy link
Contributor

Choose a reason for hiding this comment

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

There is quite a number of places with hard-coded 0.1 now, but I'm not sure we have a nice place to define a constant for this.

0.1 seems overly slow to me though, I would have picked 0.5 myself.
Maybe we want to haggle over the exact number in the maintainer meeting next week?

Copy link
Contributor Author

@felixvd felixvd Feb 19, 2020

Choose a reason for hiding this comment

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

I think we mostly need to decide which situation the default value should be for. In my opinion, it should be a safe ballpen mode for new users, which leaves them enough time to hit the emergency switch (which they will invariably not have in their hand) in case they accidentally send a motion request that does not do what they expected. E.g. the IK flipped and the robot is doing a large motion, or the robot hits something that wasn't represented in the environment (like the robot base), etc.

Choosing a "very safe" default value and expecting the user to adjust the speed to when they are ready is probably better than the opposite.

I tested a few parameter values with our UR5 to check which speeds would still be surprising a user in this type of situation. 0.5 is barely different from full speed for small motions, 0.2 seemed to be still pretty fast, and 0.1 seemed safe. 0.1 for a UR5 is about 10 cm/s in most configurations, which I think is a good compromise.

@felixvd
Copy link
Contributor Author

felixvd commented Feb 19, 2020

I updated the PR with small changes. We can talk about the actual value in the meeting if you like.

A last comment is that I think max_X_scaling_factor vs X_scaling_factor should probably be unified. The former is used in the existing code, the latter is what I wrote reflexively for the default parameters. I think I prefer the latter, but I doubt it's worth changing the nomenclature everywhere else.

@rhaschke
Copy link
Contributor

A last comment is that I think max_X_scaling_factor vs X_scaling_factor should probably be unified. The former is used in the existing code, the latter is what I wrote reflexively for the default parameters.

Actually you used default_X_scaling_factor for the name in the yaml config file.
For me that is fine.

@felixvd
Copy link
Contributor Author

felixvd commented Feb 20, 2020

Yes, I used default_X_scaling_factor instead of default_max_X_scaling_factor. I don't think it's a big deal either, but I figured it's worth noting.

There has to be a warning-free way to do so.
@felixvd
Copy link
Contributor Author

felixvd commented Feb 25, 2020

If this is good with you after your last change @v4hn, the only tests that are failing are the code coverage, so I think this is ready to merge.

@rhaschke
Copy link
Contributor

We wanted to discuss the actual numbers for the scaling factors... So not ready to merge yet.

@v4hn
Copy link
Contributor

v4hn commented Feb 27, 2020

@felixvd: The maintainer meeting just agreed to have the default of 0.1.

At the same time, we need prominent information (or better a tutorial page) on how to set the default scaling factors also for existing moveit configurations.
Could you do that too?

@felixvd
Copy link
Contributor Author

felixvd commented Feb 28, 2020

I'll do it next week, after the IROS deadline :)

I will add a ToDo list to the first post of this thread.

@rhaschke
Copy link
Contributor

rhaschke commented Mar 5, 2020

@v4hn Is this ready for merging?

@felixvd
Copy link
Contributor Author

felixvd commented Mar 6, 2020

I'll update it soon. I was still busy with the video submission deadline that is in 15 minutes.

@v4hn
Copy link
Contributor

v4hn commented Mar 6, 2020 via email

@felixvd
Copy link
Contributor Author

felixvd commented Mar 7, 2020

I added a mention in MIGRATION.md and the documentation of all interface functions that change the scaling factors, and filed the corresponding PR for the tutorials.

I think the only other thing to do would be to post a pre-emptive ROS answers question "Why is MoveIt so slow?"

@v4hn
Copy link
Contributor

v4hn commented Mar 7, 2020

I added a mention in MIGRATION.md

You didn't push a change to the file as part of this request.

I think the only other thing to do would be to post a pre-emptive ROS answers question "Why is MoveIt so slow?"

Could you do that please? Aside from these things, this is good to go.

@felixvd
Copy link
Contributor Author

felixvd commented Mar 9, 2020

I forgot to push the branch from the office 🙄I just fixed that and rebased.

The ROS answers question is here.

Copy link
Contributor

@rhaschke rhaschke left a comment

Choose a reason for hiding this comment

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

LGTM.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
awaits 2nd review one maintainer approved this request
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants