Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -86,9 +86,6 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
* @brief Function to perform some user-defined operation upon cancellation of the action
*/
BT::NodeStatus on_cancelled() override;

private:
bool initialized_;
};

} // namespace nav2_behavior_tree
Expand Down
6 changes: 2 additions & 4 deletions nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ DriveOnHeadingAction::DriveOnHeadingAction(
const std::string & xml_tag_name,
const std::string & action_name,
const BT::NodeConfiguration & conf)
: BtActionNode<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf),
initialized_(false)
: BtActionNode<nav2_msgs::action::DriveOnHeading>(xml_tag_name, action_name, conf)
{
}

Expand All @@ -47,12 +46,11 @@ void DriveOnHeadingAction::initialize()
goal_.speed = speed;
goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance);
goal_.disable_collision_checks = disable_collision_checks;
initialized_ = true;
}

void DriveOnHeadingAction::on_tick()
{
if (!initialized_) {
if (!BT::isStatusActive(status())) {
initialize();
}
}
Expand Down
Loading