Skip to content

Commit

Permalink
[behavior_tree] don't repeat yourself in "blackboard->set" (ros-navig…
Browse files Browse the repository at this point in the history
…ation#4074)

* don't repeat yourself: templates in tests

Signed-off-by: Davide Faconti <[email protected]>

* misse change

Signed-off-by: Davide Faconti <[email protected]>

---------

Signed-off-by: Davide Faconti <[email protected]>
Signed-off-by: Brice <[email protected]>
  • Loading branch information
facontidavide authored and BriceRenaudeau committed Jan 29, 2024
1 parent a952562 commit b917429
Show file tree
Hide file tree
Showing 41 changed files with 100 additions and 100 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ bool BtActionServer<ActionT>::loadBehaviorTree(const std::string & bt_xml_filena
try {
tree_ = bt_->createTreeFromFile(filename, blackboard_);
for (auto & blackboard : tree_.blackboard_stack) {
blackboard->set<rclcpp::Node::SharedPtr>("node", client_node_);
blackboard->set("node", client_node_);
blackboard->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);
blackboard->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);
blackboard->set<std::chrono::milliseconds>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class AssistedTeleopActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -71,8 +71,8 @@ class AssistedTeleopActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("number_recoveries", 0);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class CancelAssistedTeleopActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class BackUpActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -71,8 +71,8 @@ class BackUpActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("number_recoveries", 0);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class CancelBackUpActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand Down
18 changes: 9 additions & 9 deletions nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,14 +140,14 @@ class FibonacciAction : public nav2_behavior_tree::BtActionNode<test_msgs::actio

BT::NodeStatus on_success() override
{
config().blackboard->set<std::vector<int>>("sequence", result_.result->sequence);
config().blackboard->set("sequence", result_.result->sequence);
return BT::NodeStatus::SUCCESS;
}

BT::NodeStatus on_cancelled() override
{
config().blackboard->set<std::vector<int>>("sequence", result_.result->sequence);
config().blackboard->set<bool>("on_cancelled_triggered", true);
config().blackboard->set("sequence", result_.result->sequence);
config().blackboard->set("on_cancelled_triggered", true);
return BT::NodeStatus::SUCCESS;
}

Expand All @@ -170,12 +170,12 @@ class BTActionNodeTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
config_->blackboard->set("node", node_);
config_->blackboard->set<std::chrono::milliseconds>("server_timeout", 20ms);
config_->blackboard->set<std::chrono::milliseconds>("bt_loop_duration", 10ms);
config_->blackboard->set<std::chrono::milliseconds>("wait_for_service_timeout", 1000ms);
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<bool>("on_cancelled_triggered", false);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("on_cancelled_triggered", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down Expand Up @@ -303,7 +303,7 @@ TEST_F(BTActionNodeTestFixture, test_server_timeout_success)
// reset state variables
ticks = 0;
result = BT::NodeStatus::RUNNING;
config_->blackboard->set<bool>("on_cancelled_triggered", false);
config_->blackboard->set("on_cancelled_triggered", false);

// main BT execution loop
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
Expand Down Expand Up @@ -382,7 +382,7 @@ TEST_F(BTActionNodeTestFixture, test_server_timeout_failure)
// reset state variables
ticks = 0;
result = BT::NodeStatus::RUNNING;
config_->blackboard->set<bool>("on_cancelled_triggered", false);
config_->blackboard->set("on_cancelled_triggered", false);

// main BT execution loop
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
Expand Down Expand Up @@ -456,7 +456,7 @@ TEST_F(BTActionNodeTestFixture, test_server_cancel)

// reset state variable
ticks = 0;
config_->blackboard->set<bool>("on_cancelled_triggered", false);
config_->blackboard->set("on_cancelled_triggered", false);
result = BT::NodeStatus::RUNNING;

// main BT execution loop
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -56,8 +56,8 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("number_recoveries", 0);

factory_->registerNodeType<nav2_behavior_tree::ClearEntireCostmapService>("ClearEntireCostmap");
}
Expand Down Expand Up @@ -133,7 +133,7 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -145,8 +145,8 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("number_recoveries", 0);

factory_->registerNodeType<nav2_behavior_tree::ClearCostmapExceptRegionService>(
"ClearCostmapExceptRegion");
Expand Down Expand Up @@ -228,7 +228,7 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -240,8 +240,8 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set<int>("number_recoveries", 0);
config_->blackboard->set("initial_pose_received", false);
config_->blackboard->set("number_recoveries", 0);

factory_->registerNodeType<nav2_behavior_tree::ClearCostmapAroundRobotService>(
"ClearCostmapAroundRobot");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -79,7 +79,7 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -77,7 +77,7 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class CancelControllerActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class ControllerSelectorTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
config_->blackboard->set("node", node_);

BT::NodeBuilder builder = [](const std::string & name, const BT::NodeConfiguration & config) {
return std::make_unique<nav2_behavior_tree::ControllerSelector>(name, config);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class DriveOnHeadingActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -72,7 +72,7 @@ class DriveOnHeadingActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class CancelDriveOnHeadingTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class FollowPathActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -70,7 +70,7 @@ class FollowPathActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down Expand Up @@ -130,7 +130,7 @@ TEST_F(FollowPathActionTestFixture, test_tick)
nav_msgs::msg::Path path;
path.poses.resize(1);
path.poses[0].pose.position.x = 1.0;
config_->blackboard->set<nav_msgs::msg::Path>("path", path);
config_->blackboard->set("path", path);

// tick until node succeeds
while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) {
Expand All @@ -150,7 +150,7 @@ TEST_F(FollowPathActionTestFixture, test_tick)

// set new goal
path.poses[0].pose.position.x = -2.5;
config_->blackboard->set<nav_msgs::msg::Path>("path", path);
config_->blackboard->set("path", path);

while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) {
tree_->rootNode()->executeTick();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class GoalCheckerSelectorTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
config_->blackboard->set("node", node_);

BT::NodeBuilder builder = [](const std::string & name, const BT::NodeConfiguration & config) {
return std::make_unique<nav2_behavior_tree::GoalCheckerSelector>(name, config);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -73,9 +73,9 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);
std::vector<geometry_msgs::msg::PoseStamped> poses;
config_->blackboard->set<std::vector<geometry_msgs::msg::PoseStamped>>(
config_->blackboard->set(
"goals", poses);

BT::NodeBuilder builder =
Expand Down Expand Up @@ -136,7 +136,7 @@ TEST_F(NavigateThroughPosesActionTestFixture, test_tick)
poses.resize(1);
poses[0].pose.position.x = -2.5;
poses[0].pose.orientation.x = 1.0;
config_->blackboard->set<std::vector<geometry_msgs::msg::PoseStamped>>("goals", poses);
config_->blackboard->set("goals", poses);

// tick until node succeeds
while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class NavigateToPoseActionTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -71,7 +71,7 @@ class NavigateToPoseActionTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

BT::NodeBuilder builder =
[](const std::string & name, const BT::NodeConfiguration & config)
Expand Down Expand Up @@ -145,7 +145,7 @@ TEST_F(NavigateToPoseActionTestFixture, test_tick)
// set new goal
pose.pose.position.x = -2.5;
pose.pose.orientation.x = 1.0;
config_->blackboard->set<geometry_msgs::msg::PoseStamped>("goal", pose);
config_->blackboard->set("goal", pose);

while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) {
tree_->rootNode()->executeTick();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class PlannerSelectorTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>("node", node_);
config_->blackboard->set("node", node_);

BT::NodeBuilder builder = [](const std::string & name, const BT::NodeConfiguration & config) {
return std::make_unique<nav2_behavior_tree::PlannerSelector>(name, config);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test
// Create the blackboard that will be shared by all of the nodes in the tree
config_->blackboard = BT::Blackboard::create();
// Put items on the blackboard
config_->blackboard->set<rclcpp::Node::SharedPtr>(
config_->blackboard->set(
"node",
node_);
config_->blackboard->set<std::chrono::milliseconds>(
Expand All @@ -56,7 +56,7 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test
config_->blackboard->set<std::chrono::milliseconds>(
"wait_for_service_timeout",
std::chrono::milliseconds(1000));
config_->blackboard->set<bool>("initial_pose_received", false);
config_->blackboard->set("initial_pose_received", false);

factory_->registerNodeType<nav2_behavior_tree::ReinitializeGlobalLocalizationService>(
"ReinitializeGlobalLocalization");
Expand Down
Loading

0 comments on commit b917429

Please sign in to comment.