Skip to content

Commit 643b7db

Browse files
committed
fix initializing in drive on heading action node
Signed-off-by: Johannes Plapp <johannes.plapp@logivations.com>
1 parent 8626be5 commit 643b7db

File tree

2 files changed

+2
-7
lines changed

2 files changed

+2
-7
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -86,9 +86,6 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
8686
* @brief Function to perform some user-defined operation upon cancellation of the action
8787
*/
8888
BT::NodeStatus on_cancelled() override;
89-
90-
private:
91-
bool initialized_;
9289
};
9390

9491
} // namespace nav2_behavior_tree

nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,7 @@ DriveOnHeadingAction::DriveOnHeadingAction(
2424
const std::string & xml_tag_name,
2525
const std::string & action_name,
2626
const BT::NodeConfiguration & conf)
27-
: BtActionNode<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf),
28-
initialized_(false)
27+
: BtActionNode<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf)
2928
{
3029
}
3130

@@ -47,12 +46,11 @@ void DriveOnHeadingAction::initialize()
4746
goal_.speed = speed;
4847
goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
4948
goal_.disable_collision_checks = disable_collision_checks;
50-
initialized_ = true;
5149
}
5250

5351
void DriveOnHeadingAction::on_tick()
5452
{
55-
if (!initialized_) {
53+
if (!BT::isStatusActive(status())) {
5654
initialize();
5755
}
5856
}

0 commit comments

Comments
 (0)