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

Option for controller-specific duration parameters #785

Merged
merged 2 commits into from
Jul 4, 2018

Conversation

2scholz
Copy link
Contributor

@2scholz 2scholz commented Mar 1, 2018

allowed_execution_duration_scaling and allowed_goal_duration_margin were previously set globally and could not be specified for individual controllers.
This patch makes it possible to define the values for controllers in the controller_list parameter (they can be specified in the controllers.yaml).
A short example:

controller_list:
 - name: example_controller
   type: FollowJointTrajectory
   allowed_execution_duration_scaling: 1.2
   allowed_goal_duration_margin: 0.5

The global value is still used whenever no controller-specific value was defined.

@v4hn

@v4hn
Copy link
Contributor

v4hn commented Mar 2, 2018

I supervised the development of this patch.

These values are controller-specific to begin with, but nobody complained before that they could not be set for individual controllers...
In our use-case the execution time of our robotic gripper can deviate quite a lot from the planned trajectory, but the robotic arm it is attached to is very reliable.

Should not be cherry-picked because it breaks ABI.

Please review @davetcoleman @rhaschke (sorry Robert, I know you're busy :))

Copy link
Member

@davetcoleman davetcoleman left a comment

Choose a reason for hiding this comment

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

Great improvement! Just a few cleanup feedback. Also please add to tutorials this new option, in this tutorial i believe:
http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/fake_controller_manager_tutorial.html

@@ -343,6 +343,10 @@ class TrajectoryExecutionManager
bool execution_duration_monitoring_;
double allowed_execution_duration_scaling_;
Copy link
Member

Choose a reason for hiding this comment

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

add comment above that these are the 'global' variables, in contrast to the controller specific ones

@@ -129,6 +129,25 @@ void TrajectoryExecutionManager::initialize()
else
allowed_goal_duration_margin_ = DEFAULT_CONTROLLER_GOAL_DURATION_MARGIN;

XmlRpc::XmlRpcValue controller_list;
Copy link
Member

Choose a reason for hiding this comment

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

add comment above saying what this section does

also lets just move this into a private function loadControllerParams()

// expected duration is the duration of the longest part
expected_trajectory_duration =
std::max(d * current_scaling + ros::Duration(current_margin), expected_trajectory_duration);
}
Copy link
Member

Choose a reason for hiding this comment

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

awesome!

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 to Dave's comments. Otherwise LGTM.

expected_trajectory_duration = expected_trajectory_duration * allowed_execution_duration_scaling_ +
ros::Duration(allowed_goal_duration_margin_);
// use controller-specific values if defined
const double current_scaling = controller_allowed_execution_duration_scaling_.count(context.controllers_[i]) > 0 ?
Copy link
Contributor

Choose a reason for hiding this comment

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

This is inefficient, as the map is searched two times: once for count() and once for access.
Better use find() to search once and subsequently compare the retrieved iterator against end().

@2scholz
Copy link
Contributor Author

2scholz commented Apr 5, 2018

Thanks for the feedback. I added the requested changes to the commit and made a pull request to add the option in the tutorials (see moveit/moveit_tutorials#161)

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 just noticed that the global parameters actually moved into the namespace trajectory_execution as stated here and are handled by dynamic reconfigure.

It feels strange, that the controller-specific values are not handled by dynamic reconfigure... I'm not sure dynamic reconfigure can handle a dynamic number of parameters. However, it's worth to check!

@2scholz
Copy link
Contributor Author

2scholz commented Apr 6, 2018

The parameters handled by dynamic reconfigure need to be declared in the .cfg file.
There is an old open issue where the possibility to add parameters at runtime was discussed, but nothing came of it yet.

@rhaschke
Copy link
Contributor

@2scholz Could you please rebase? Also, discuss/document the relationship of the controller-specific variables and their dynamically reconfigurable global counterparts.
I guess, controller-specific variables override any globals.

allowed_execution_duration_scaling and allowed_goal_duration_margin
were previously set globally for every controller.
Now it is possible to define these value for each controller specifically
in the controller_list parameter.
The global value is still used, in case no controller-specific value was
defined.
@2scholz
Copy link
Contributor Author

2scholz commented May 30, 2018

I rebased the branch.
I changed the comment in the header file above the controller-specific variables a bit to make it clearer that these override the global ones.
Additionally a description of the difference between the global and controller-specific values was added in the pull request for the documentation: moveit/moveit_tutorials#161

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 rebasing. Please comment on my concerns regarding dynamic reconfigurability.


expected_trajectory_duration = expected_trajectory_duration * allowed_execution_duration_scaling_ +
ros::Duration(allowed_goal_duration_margin_);
// use controller-specific values if defined
Copy link
Contributor

Choose a reason for hiding this comment

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

Please add a comment here, that the global parameters are dynamically reconfigurable (and thus might change from call to call). If there are controller-specific values defined, they override any global parameters - even if set through dynamic reconfigure.

That's the point, I'm feeling still uncomfortable with. If the user has changed the global parameters, they will not take effect and the user isn't notified about that fact...
Did you considered to use the minimum of global and specific?

Copy link
Contributor

Choose a reason for hiding this comment

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

@rhaschke We were discussing over here where exactly you wanted to have more documentation and @2scholz added more explanation to the tutorial already: moveit/moveit_tutorials#161 .

I see your concerns about dynamic_reconfigure not working, but the only way to get around this is to patch dynamic_reconfigure and allow runtime variables in there. I don't like that very much.

Neither minimum nor maximum operator make sense in practice.

Copy link
Contributor

Choose a reason for hiding this comment

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

I think, there should be a reminder in the source code (at indicated line 1422), that controller-specific values will override dynamically configurable globals. I don't yet have a solution for this as well, but there should be a reminder in the source code if we come up with a solution later...

Eventually there should also be a warning (once) if global parameters have changed through dynamic reconfigure, but are overridden by controller-specific ones. All you need to do for this, is to keep track of the dyn-reconfig-callbacks (I think there is always one to set the initial value).

Copy link
Contributor

Choose a reason for hiding this comment

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

I just added a comment there.

@rhaschke rhaschke merged commit 43dd845 into moveit:kinetic-devel Jul 4, 2018
rhaschke pushed a commit to ubi-agni/moveit that referenced this pull request Jul 4, 2018
Additionally to the global duration parameters `trajectory_execution/allowed_execution_duration_scaling` and `trajectory_execution/allowed_goal_duration_margin`, allow for controller-specific overrides,
named `allowed_execution_duration_scaling` and `allowed_goal_duration_margin`.

As opposed to the global values, the contoller-specific ones cannot be dynamically reconfigured at runtime. The global value is still used, when no controller-specific value was defined.
dg-shadow pushed a commit to shadow-robot/moveit that referenced this pull request Jul 30, 2018
Additionally to the global duration parameters `trajectory_execution/allowed_execution_duration_scaling` and `trajectory_execution/allowed_goal_duration_margin`, allow for controller-specific overrides,
named `allowed_execution_duration_scaling` and `allowed_goal_duration_margin`.

As opposed to the global values, the contoller-specific ones cannot be dynamically reconfigured at runtime. The global value is still used, when no controller-specific value was defined.
mayman99 pushed a commit to mayman99/moveit that referenced this pull request Aug 25, 2018
Additionally to the global duration parameters `trajectory_execution/allowed_execution_duration_scaling` and `trajectory_execution/allowed_goal_duration_margin`, allow for controller-specific overrides,
named `allowed_execution_duration_scaling` and `allowed_goal_duration_margin`.

As opposed to the global values, the contoller-specific ones cannot be dynamically reconfigured at runtime. The global value is still used, when no controller-specific value was defined.
JafarAbdi pushed a commit to JafarAbdi/moveit that referenced this pull request Mar 24, 2022
…tching (moveit#785)

* Update controller_manager_plugin to fix MoveIt-managed controller switching

* add documentation about mutex

* add a comment about how interface names are modified in-place
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.

None yet

4 participants