moveit
moveit copied to clipboard
Can't connect to MoveGroupAction server by using getMoveGroupClient
Description
I want to execute a trajectory asynchronously so that I can monitor the execution and maybe abord it at the same time. Quite similar to @ #1215
Your environment
- ROS Distro: [Melodic]
- OS Version:Ubuntu 18.04
- Source or Binary build?
- binary: ros-melidic-moveit
Steps to reproduce
a part of my code is like:
move_group_->asyncExecute(plan);
ROS_INFO("move_action_client: %s", move_group_->getMoveGroupClient().getState().toString().c_str());
ros::Rate rate(10);
while (!move_group_->getMoveGroupClient().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_group_->getMoveGroupClient().getState().toString().c_str(),
move_group_->getMoveGroupClient().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;
}
Actual behaviour
I got move_action_client: LOST
Thanks for reporting an issue. Because we're a volunteer community, providing a pull request with suggested changes is always welcomed.
Sorry that this has been left sitting for so long. Have you been able to solve this? It looks like your roscore process might have restarted and your nodes can't find each other.
Does the !move_group_->getMoveGroupClient().getState().isDone() actually tell us if the trajectory has terminated in realtime? I can't find this in the documentation and several people have said the API does not have that capability.
Does the !move_group_->getMoveGroupClient().getState().isDone() actually tell us if the trajectory has terminated in realtime?
That strongly depends on what you mean by "realtime" here. It will become true when the action server finished with the trajectory. However, depending on your configuration and underlying hardware that can mean different things, possible cases include
- the robot arrived at the goal location and has joint velocities close to zero and
- the robot controller received the last waypoint of the trajectory and is moving towards it
And of course either way you get the additionally ROS communication overhead to send the result message from the action server to the client.
By realtime I just mean that if I condition a while loop on it like: while (!move_group_->getMoveGroupClient().getState().isDone() && ros::ok()){ } that it will continue to query the client and execute the while loop while the trajectory is being executed until the action client returns based on one of the possible conditions you described. This is my expected behavior.
while (!move_group_->getMoveGroupClient().getState().isDone() && ros::ok()){}
That should work as long as you spin your ROS message subscribers somewhere (the action client will wait for a message on a subscriber).
You could do that either via AsyncSpinner
or by calling ros::spinOnce()
in the body of the loop.
There's also always the possibility to waitForResult()
in a separate thread and use your own signalling.
Thank you.
On Oct 6, 2021, at 2:14 PM, Michael Görner @.***> wrote:
while (!move_group_->getMoveGroupClient().getState().isDone() && ros::ok()){}
That should work as long as you spin your ROS message subscribers somewhere (the action client will wait for a message on a subscriber). You could do that either via
AsyncSpinner
or by callingros::spinOnce()
in the body of the loop. There's also always the possibility towaitForResult()
in a separate thread and use your own signalling. — You are receiving this because you commented. Reply to this email directly, view it on GitHub, or unsubscribe. Triage notifications on the go with GitHub Mobile for iOS or Android.
I tried the above method and move_group_->getMoveGroupClient().getState() always returns success and the move it console says the trajectory was preempted. If I use the regular execute function, I can complete the trajectory but obviously cannot monitor it. Any idea what the issue could be?
Well, it preempts itself because I blocked on that status variable, which is somehow returning SUCCESS when the robot is still moving. A better question is why would it return SUCCESS before the trajectory is complete?
Well, it preempts itself because I blocked on that status variable, which is somehow returning SUCCESS when the robot is still moving. A better question is why would it return SUCCESS before the trajectory is complete?
hi, I've found the reason of your question:
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().
ps: you should change the source code directly
Well, it preempts itself because I blocked on that status variable, which is somehow returning SUCCESS when the robot is still moving. A better question is why would it return SUCCESS before the trajectory is complete?
hi, I've found the reason of your question: I discovered there is a bug in current
getMoveGroupClient()
. To get the execution state ofaysncExecute()
, the return client should bereturn * execute_action_client_
instead of*move_action_client_
. The latter one only works when you usemove()
andplan(
), whileexecute_action_client_
will always work inaysncExecute().
ps: you should change the source code directly
Thanks. This is exactly what I was looking for. Devils are always in the details.