Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
2
210910794
Manage
Activity
Members
Labels
Plan
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Deploy
Releases
Package Registry
Operate
Terraform modules
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Summer2021
210910794
Commits
25b45bd2
Commit
25b45bd2
authored
5 years ago
by
bpwilcox
Browse files
Options
Downloads
Patches
Plain Diff
simplify should cancel check
parent
c589e937
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
+26
-14
26 additions, 14 deletions
...havior_tree/include/nav2_behavior_tree/bt_action_node.hpp
with
26 additions
and
14 deletions
nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
+
26
−
14
View file @
25b45bd2
...
...
@@ -163,28 +163,40 @@ new_goal_received:
// make sure to cancel the ROS2 action if it is still running.
void
halt
()
override
{
// Shut the node down if it is currently running
if
(
status
()
==
BT
::
NodeStatus
::
RUNNING
)
{
rclcpp
::
spin_some
(
node_
);
// Check if the goal is still executing
auto
status
=
goal_handle_
->
get_status
();
if
(
status
==
action_msgs
::
msg
::
GoalStatus
::
STATUS_ACCEPTED
||
status
==
action_msgs
::
msg
::
GoalStatus
::
STATUS_EXECUTING
)
if
(
should_cancel_goal
())
{
auto
future_cancel
=
action_client_
->
async_cancel_goal
(
goal_handle_
);
if
(
rclcpp
::
spin_until_future_complete
(
node_
,
future_cancel
)
!=
rclcpp
::
executor
::
FutureReturnCode
::
SUCCESS
)
{
auto
future_cancel
=
action_client_
->
async_cancel_goal
(
goal_handle_
);
if
(
rclcpp
::
spin_until_future_complete
(
node_
,
future_cancel
)
!=
rclcpp
::
executor
::
FutureReturnCode
::
SUCCESS
)
{
RCLCPP_ERROR
(
node_
->
get_logger
(),
"Failed to cancel action server for %s"
,
action_name_
.
c_str
());
}
RCLCPP_ERROR
(
node_
->
get_logger
(),
"Failed to cancel action server for %s"
,
action_name_
.
c_str
());
}
}
setStatus
(
BT
::
NodeStatus
::
IDLE
);
CoroActionNode
::
halt
();
}
protected
:
bool
should_cancel_goal
()
{
// Shut the node down if it is currently running
if
(
status
()
!=
BT
::
NodeStatus
::
RUNNING
)
{
return
false
;
}
rclcpp
::
spin_some
(
node_
);
auto
status
=
goal_handle_
->
get_status
();
// Check if the goal is still executing
if
(
status
==
action_msgs
::
msg
::
GoalStatus
::
STATUS_ACCEPTED
||
status
==
action_msgs
::
msg
::
GoalStatus
::
STATUS_EXECUTING
)
{
return
true
;
}
return
false
;
}
const
std
::
string
action_name_
;
typename
std
::
shared_ptr
<
rclcpp_action
::
Client
<
ActionT
>>
action_client_
;
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment