forked from ros-navigation/navigation2
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Draft: Added GoalUpdatedController BT plugin node (ros-navigation#3044)
* first draft for goal updated controller Signed-off-by: relffok <[email protected]> * added goal_updated_controller to all yamls * added GoalUpdatedController API * added GoaUpdatedController to default plugins * removed first_time param * added test for GoalUpdatedController * linter fix
- Loading branch information
Showing
14 changed files
with
295 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
68 changes: 68 additions & 0 deletions
68
nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
// Copyright (c) 2018 Intel Corporation | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__GOAL_UPDATED_CONTROLLER_HPP_ | ||
#define NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__GOAL_UPDATED_CONTROLLER_HPP_ | ||
|
||
#include <chrono> | ||
#include <string> | ||
#include <vector> | ||
|
||
#include "behaviortree_cpp_v3/decorator_node.h" | ||
|
||
#include "rclcpp/rclcpp.hpp" | ||
#include "geometry_msgs/msg/pose_stamped.hpp" | ||
|
||
namespace nav2_behavior_tree | ||
{ | ||
|
||
/** | ||
* @brief A BT::DecoratorNode that ticks its child if the goal was updated | ||
*/ | ||
class GoalUpdatedController : public BT::DecoratorNode | ||
{ | ||
public: | ||
/** | ||
* @brief A constructor for nav2_behavior_tree::GoalUpdatedController | ||
* @param name Name for the XML tag for this node | ||
* @param conf BT node configuration | ||
*/ | ||
GoalUpdatedController( | ||
const std::string & name, | ||
const BT::NodeConfiguration & conf); | ||
|
||
/** | ||
* @brief Creates list of BT ports | ||
* @return BT::PortsList Containing node-specific ports | ||
*/ | ||
static BT::PortsList providedPorts() | ||
{ | ||
return {}; | ||
} | ||
|
||
private: | ||
/** | ||
* @brief The main override required by a BT action | ||
* @return BT::NodeStatus Status of tick execution | ||
*/ | ||
BT::NodeStatus tick() override; | ||
|
||
bool goal_was_updated_; | ||
geometry_msgs::msg::PoseStamped goal_; | ||
std::vector<geometry_msgs::msg::PoseStamped> goals_; | ||
}; | ||
|
||
} // namespace nav2_behavior_tree | ||
|
||
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__DECORATOR__GOAL_UPDATED_CONTROLLER_HPP_ |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
88 changes: 88 additions & 0 deletions
88
nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,88 @@ | ||
// Copyright (c) 2018 Intel Corporation | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include <chrono> | ||
#include <string> | ||
|
||
#include "rclcpp/rclcpp.hpp" | ||
#include "geometry_msgs/msg/pose_stamped.hpp" | ||
#include "behaviortree_cpp_v3/decorator_node.h" | ||
#include "nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp" | ||
|
||
|
||
namespace nav2_behavior_tree | ||
{ | ||
|
||
GoalUpdatedController::GoalUpdatedController( | ||
const std::string & name, | ||
const BT::NodeConfiguration & conf) | ||
: BT::DecoratorNode(name, conf) | ||
{ | ||
} | ||
|
||
BT::NodeStatus GoalUpdatedController::tick() | ||
{ | ||
if (status() == BT::NodeStatus::IDLE) { | ||
// Reset since we're starting a new iteration of | ||
// the goal updated controller (moving from IDLE to RUNNING) | ||
|
||
config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", goals_); | ||
config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", goal_); | ||
|
||
goal_was_updated_ = true; | ||
} | ||
|
||
setStatus(BT::NodeStatus::RUNNING); | ||
|
||
std::vector<geometry_msgs::msg::PoseStamped> current_goals; | ||
config().blackboard->get<std::vector<geometry_msgs::msg::PoseStamped>>("goals", current_goals); | ||
geometry_msgs::msg::PoseStamped current_goal; | ||
config().blackboard->get<geometry_msgs::msg::PoseStamped>("goal", current_goal); | ||
|
||
if (goal_ != current_goal || goals_ != current_goals) { | ||
goal_ = current_goal; | ||
goals_ = current_goals; | ||
goal_was_updated_ = true; | ||
} | ||
|
||
// The child gets ticked the first time through and any time the goal has | ||
// changed or preempted. In addition, once the child begins to run, it is ticked each time | ||
// 'til completion | ||
if ((child_node_->status() == BT::NodeStatus::RUNNING) || goal_was_updated_) { | ||
goal_was_updated_ = false; | ||
const BT::NodeStatus child_state = child_node_->executeTick(); | ||
|
||
switch (child_state) { | ||
case BT::NodeStatus::RUNNING: | ||
return BT::NodeStatus::RUNNING; | ||
|
||
case BT::NodeStatus::SUCCESS: | ||
return BT::NodeStatus::SUCCESS; | ||
|
||
case BT::NodeStatus::FAILURE: | ||
default: | ||
return BT::NodeStatus::FAILURE; | ||
} | ||
} | ||
|
||
return status(); | ||
} | ||
|
||
} // namespace nav2_behavior_tree | ||
|
||
#include "behaviortree_cpp_v3/bt_factory.h" | ||
BT_REGISTER_NODES(factory) | ||
{ | ||
factory.registerNodeType<nav2_behavior_tree::GoalUpdatedController>("GoalUpdatedController"); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
108 changes: 108 additions & 0 deletions
108
nav2_behavior_tree/test/plugins/decorator/test_goal_updated_controller.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,108 @@ | ||
// Copyright (c) 2018 Intel Corporation | ||
// Copyright (c) 2020 Sarthak Mittal | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include <gtest/gtest.h> | ||
#include <chrono> | ||
#include <memory> | ||
#include <set> | ||
|
||
#include "../../test_behavior_tree_fixture.hpp" | ||
#include "nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp" | ||
|
||
using namespace std::chrono; // NOLINT | ||
using namespace std::chrono_literals; // NOLINT | ||
|
||
class GoalUpdatedControllerTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixture | ||
{ | ||
public: | ||
void SetUp() | ||
{ | ||
// Setting fake goals on blackboard | ||
geometry_msgs::msg::PoseStamped goal1; | ||
goal1.header.stamp = node_->now(); | ||
std::vector<geometry_msgs::msg::PoseStamped> poses1; | ||
poses1.push_back(goal1); | ||
config_->blackboard->set("goal", goal1); | ||
config_->blackboard->set<std::vector<geometry_msgs::msg::PoseStamped>>("goals", poses1); | ||
|
||
bt_node_ = std::make_shared<nav2_behavior_tree::GoalUpdatedController>( | ||
"goal_updated_controller", *config_); | ||
dummy_node_ = std::make_shared<nav2_behavior_tree::DummyNode>(); | ||
bt_node_->setChild(dummy_node_.get()); | ||
} | ||
|
||
void TearDown() | ||
{ | ||
dummy_node_.reset(); | ||
bt_node_.reset(); | ||
} | ||
|
||
protected: | ||
static std::shared_ptr<nav2_behavior_tree::GoalUpdatedController> bt_node_; | ||
static std::shared_ptr<nav2_behavior_tree::DummyNode> dummy_node_; | ||
}; | ||
|
||
std::shared_ptr<nav2_behavior_tree::GoalUpdatedController> | ||
GoalUpdatedControllerTestFixture::bt_node_ = nullptr; | ||
std::shared_ptr<nav2_behavior_tree::DummyNode> | ||
GoalUpdatedControllerTestFixture::dummy_node_ = nullptr; | ||
|
||
TEST_F(GoalUpdatedControllerTestFixture, test_behavior) | ||
{ | ||
// Creating updated fake-goals | ||
geometry_msgs::msg::PoseStamped goal2; | ||
goal2.header.stamp = node_->now(); | ||
std::vector<geometry_msgs::msg::PoseStamped> poses2; | ||
poses2.push_back(goal2); | ||
|
||
// starting in idle | ||
EXPECT_EQ(bt_node_->status(), BT::NodeStatus::IDLE); | ||
|
||
// tick for the first time, dummy node should be ticked | ||
dummy_node_->changeStatus(BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(dummy_node_->status(), BT::NodeStatus::IDLE); | ||
|
||
// tick again with updated goal, dummy node should be ticked | ||
config_->blackboard->set("goal", goal2); | ||
dummy_node_->changeStatus(BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(dummy_node_->status(), BT::NodeStatus::IDLE); | ||
|
||
// tick again without update, dummy node should not be ticked | ||
EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING); | ||
EXPECT_EQ(dummy_node_->status(), BT::NodeStatus::IDLE); | ||
|
||
// tick again with updated goals, dummy node should be ticked | ||
config_->blackboard->set<std::vector<geometry_msgs::msg::PoseStamped>>("goals", poses2); | ||
dummy_node_->changeStatus(BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::SUCCESS); | ||
EXPECT_EQ(dummy_node_->status(), BT::NodeStatus::IDLE); | ||
} | ||
|
||
int main(int argc, char ** argv) | ||
{ | ||
::testing::InitGoogleTest(&argc, argv); | ||
|
||
// initialize ROS | ||
rclcpp::init(argc, argv); | ||
|
||
bool all_successful = RUN_ALL_TESTS(); | ||
|
||
// shutdown ROS | ||
rclcpp::shutdown(); | ||
|
||
return all_successful; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
14 changes: 14 additions & 0 deletions
14
nav2_bt_navigator/behavior_trees/navigate_w_replanning_only_if_goal_is_updated.xml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,14 @@ | ||
<!-- | ||
This Behavior Tree replans the global path only when the goal is updated. | ||
--> | ||
|
||
<root main_tree_to_execute="MainTree"> | ||
<BehaviorTree ID="MainTree"> | ||
<PipelineSequence name="NavigateWithReplanning"> | ||
<GoalUpdatedController> <!-- only tick child if goal was updated--> | ||
<ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/> | ||
</GoalUpdatedController> | ||
<FollowPath path="{path}" controller_id="FollowPath"/> | ||
</PipelineSequence> | ||
</BehaviorTree> | ||
</root> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters