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 getMoveGroupClient() to move_group_interface #1215

Merged
merged 6 commits into from
Nov 26, 2018

Conversation

mintar
Copy link
Contributor

@mintar mintar commented Nov 21, 2018

Use case: I want to execute a trajectory asynchronously while also being able to monitor its execution and perhaps abort it.

  • MoveGroupInterface::asyncMove() lets me start asynchronous execution
  • MoveGroupInterface::stop() lets me abort it
  • but there is no way to monitor the execution or get the result

This PR simply adds a getter for the internal move_action_client. This enables code like shown in the usage example below. I'm not sure that exposing the internal move_action_client is the nicest API (comments welcome), but at least it seems more elegant than replicating all of the client's API one-by-one. In the example below, I've only used getState(), getResult() and cancelGoal(); but the other methods are useful as well (for example waitForResult()).

usage example

moveit::planning_interface::MoveGroupInterface group;
// [...]
group.setNamedTarget("home");
group.plan(plan);
group.asyncMove();
std::shared_ptr<actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction> >
    move_action_client = group.getMoveActionClient();

ros::Rate rate(10);
while (!move_action_client->getState().isDone() && ros::ok()) {
  ROS_DEBUG("move_action_client: %s", move_action_client->getState().toString().c_str());
  rate.sleep();
  // to abort execution of the trajectory: `move_action_client->cancelGoal();` or `group.stop();`
}

ROS_DEBUG("move_action_client: %s %s",
          move_action_client->getState().toString().c_str(),
          move_action_client->getState().getText().c_str());

auto error_code = move_action_client->getResult()->error_code.val;

if (error_code == moveit::planning_interface::MoveItErrorCode::SUCCESS) {
  ROS_INFO("Moving to home pose SUCCESSFUL");
  return 0;
} else {
  ROS_ERROR("Moving to home pose FAILED");
  return 1;
}

TODOs

  • Required by CI: Code is auto formatted using clang-format
  • Extended the tutorials / documentation, if necessary reference
  • Created tests, which fail without this PR reference
  • Decide if this should be cherry-picked to other current ROS branches
  • While waiting for someone to review your request, please consider reviewing another open pull request to support the maintainers. You can refer to our ROS code review guide for direction

@v4hn
Copy link
Contributor

v4hn commented Nov 22, 2018 via email

@mintar
Copy link
Contributor Author

mintar commented Nov 23, 2018

I don't like the idea of sharing the action client though and would prefer to return a reference from the method. Why did you decide to use a shared_ptr instead?

Because a unique_ptr cannot be copied, so it cannot be returned. If you prefer, I could switch the return type to unique_ptr&, but is there a practical difference to shared_ptr?

For consistency it might also make sense to change the method name to getMoveGroupClient.

Done.

Do you have to write out the pointer definition, or is there a typedef you can use?

I couldn't find any existing typedef. Should I create a new one?

@mintar
Copy link
Contributor Author

mintar commented Nov 23, 2018

Regarding the return type: I could return a reference to the underlying object directly (so, a const actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction>&). Now that I think about it, that sounds even better. Is this what you meant?

I don't like the idea of sharing the action client though

Well, we're doing that anyway, no matter which return type we use.

@mintar
Copy link
Contributor Author

mintar commented Nov 23, 2018

Ok, I've made the change to the return type.

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.

Now that I think about it, that sounds even better. Is this what you meant?

Yes, that's exactly what I meant. Returning a reference to a pointer does not make a lot of sense here, that's true. :)

I don't like the idea of sharing the action client though

Well, we're doing that anyway, no matter which return type we use.

Sorry, I meant to write share ownership.
Never get on a crowded subway and review at the same time...

Two nitpicks, otherwise this looks good to me.

@mintar
Copy link
Contributor Author

mintar commented Nov 23, 2018

Ok, all requested changes are done.

@mintar mintar changed the title Add getMoveActionClient() to move_group_interface Add getMoveGroupClient() to move_group_interface Nov 23, 2018
@v4hn
Copy link
Contributor

v4hn commented Nov 23, 2018

Looks good to me. Thanks for your time @mintar 👍
Let's see what someone else has to say.

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.

For consistency, declare both methods const.

@@ -1502,6 +1505,12 @@ moveit::planning_interface::MoveItErrorCode moveit::planning_interface::MoveGrou
return impl_->move(false);
}

actionlib::SimpleActionClient<moveit_msgs::MoveGroupAction>&
moveit::planning_interface::MoveGroupInterface::getMoveGroupClient()
Copy link
Contributor

Choose a reason for hiding this comment

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

This method is missing the const specifier, while the implementation method has one.

Suggested change
moveit::planning_interface::MoveGroupInterface::getMoveGroupClient()
moveit::planning_interface::MoveGroupInterface::getMoveGroupClient() const

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Good catch, I obviously meant to make it const everywhere. Fixed!

@rhaschke rhaschke merged commit fc092cc into moveit:kinetic-devel Nov 26, 2018
@mintar
Copy link
Contributor Author

mintar commented Nov 26, 2018

Nice! That went faster than expected.

@mintar mintar deleted the get-move-action-client branch November 26, 2018 12:58
@v4hn
Copy link
Contributor

v4hn commented Nov 26, 2018

@mintar Glad you talked to me about it 👍

@davidyanghit
Copy link

hi, I discovered there is a bug in current getMoveGroupClient(). To get the execution state of aysncExecute(), the return client should be return * execute_action_client_ instead of *move_action_client_. The latter one only works when you use move() and plan(), while execute_action_client_ will always work in aysncExecute().

@simonschmeisser
Copy link
Contributor

@davidyanghit it would be really nice if you could open a new PR with your proposed changes, it's easier to understand and comment then

sjahr pushed a commit to sjahr/moveit that referenced this pull request Jun 21, 2024
* CI: More generically fix permission errors

Disable git security check for any folder.
We are running a docker container on GHA. Chances are low that this gets compromised.

* Revert changes to source Dockerfile

These are inherited from ci.
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

5 participants