Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Maintenance rolling #332

Merged
merged 7 commits into from
Nov 5, 2024
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
2 changes: 1 addition & 1 deletion plansys2_bringup/src/plansys2_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ int main(int argc, char ** argv)

rclcpp::init(argc, argv);

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

auto domain_node = std::make_shared<plansys2::DomainExpertNode>();
auto problem_node = std::make_shared<plansys2::ProblemExpertNode>();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ class BtActionNode : public BT::ActionNodeBase
};
send_goal_options.feedback_callback =
[this](typename rclcpp_action::ClientGoalHandle<ActionT>::SharedPtr,
const std::shared_ptr<const typename ActionT::Feedback> feedback) {
const std::shared_ptr<const typename ActionT::Feedback> feedback) {
on_feedback(feedback);
};

Expand Down
2 changes: 1 addition & 1 deletion plansys2_bt_actions/test/behavior_tree/transport.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<root BTCPP_format="4" main_tree_to_execute = "MainTree" >
<BehaviorTree ID="MainTree">
<Sequence name="root_sequence">
<Move name="move" goal="${arg2}" goal_reached="${goal_reached}"/>
<Move name="move" goal="{arg2}" goal_reached="{goal_reached}"/>
<OpenGripper name="open_gripper"/>
<CloseGripper name="close_gripper"/>
</Sequence>
Expand Down
4 changes: 2 additions & 2 deletions plansys2_bt_actions/test/unit/bt_action_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ TEST(bt_actions, bt_action)

bt_action->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);

rclcpp::executors::MultiThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;
exe.add_node(bt_action->get_node_base_interface());
exe.add_node(lc_node->get_node_base_interface());

Expand Down Expand Up @@ -282,7 +282,7 @@ TEST(bt_actions, cancel_bt_action)

bt_action->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);

rclcpp::executors::MultiThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;
exe.add_node(bt_action->get_node_base_interface());
exe.add_node(lc_node->get_node_base_interface());

Expand Down
2 changes: 1 addition & 1 deletion plansys2_domain_expert/src/domain_expert_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv);
auto node = std::make_shared<plansys2::DomainExpertNode>();

rclcpp::executors::MultiThreadedExecutor executor;
rclcpp::experimental::executors::EventsExecutor executor;
executor.add_node(node->get_node_base_interface());
executor.spin();
executor.remove_node(node->get_node_base_interface());
Expand Down
4 changes: 2 additions & 2 deletions plansys2_domain_expert/test/unit/domain_expert_node_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ TEST(domain_expert, lifecycle)
std::string pkgpath = ament_index_cpp::get_package_share_directory("plansys2_domain_expert");

domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple.pddl"});
rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());

Expand Down Expand Up @@ -105,7 +105,7 @@ TEST(domain_expert, lifecycle_error)
std::string pkgpath = ament_index_cpp::get_package_share_directory("plansys2_domain_expert");

domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_2_error.pddl"});
rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());

Expand Down
2 changes: 1 addition & 1 deletion plansys2_executor/src/plansys2_executor/ComputeBT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ ComputeBT::computeBTCallback(
domain_node_->set_parameter({"model_file", domain_filename});
problem_node_->set_parameter({"model_file", domain_filename});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node_->get_node_base_interface());
exe.add_node(problem_node_->get_node_base_interface());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@ ExecuteAction::halt()
size_t delim = action.find(":");
auto action_expr = action.substr(0, delim);

if (action_map_ == nullptr || (*action_map_)[action].action_executor == nullptr) {
return;
}

if ((*action_map_)[action].action_executor->get_status() == BT::NodeStatus::RUNNING) {
(*action_map_)[action].action_executor->cancel();
}
Expand Down
4 changes: 2 additions & 2 deletions plansys2_executor/test/unit/action_execution_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ TEST(action_execution, protocol_basic)

move_action_node->set_parameter({"action_name", "move"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(test_node);
exe.add_node(test_lf_node->get_node_base_interface());
Expand Down Expand Up @@ -240,7 +240,7 @@ TEST(action_execution, protocol_cancelation)

move_action_node->set_parameter({"action_name", "move"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(test_node);
exe.add_node(test_lf_node->get_node_base_interface());
Expand Down
10 changes: 5 additions & 5 deletions plansys2_executor/test/unit/bt_node_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ TEST(problem_expert, wait_overall_req_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -186,7 +186,7 @@ TEST(problem_expert, wait_atstart_req_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -302,7 +302,7 @@ TEST(problem_expert, wait_atend_req_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -416,7 +416,7 @@ TEST(problem_expert, at_start_effect_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -535,7 +535,7 @@ TEST(problem_expert, at_end_effect_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
6 changes: 3 additions & 3 deletions plansys2_executor/test/unit/bt_node_test_charging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ TEST(problem_expert, wait_atstart_req_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -192,7 +192,7 @@ TEST(problem_expert, apply_atstart_effect_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -319,7 +319,7 @@ TEST(problem_expert, apply_atend_effect_test)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
6 changes: 3 additions & 3 deletions plansys2_executor/test/unit/execution_tree_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ TEST(executiotest_noden_tree, bt_builder_factory)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -192,7 +192,7 @@ TEST(executiotest_noden_tree, bt_builder_factory_2)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -332,7 +332,7 @@ TEST(executiotest_noden_tree, bt_builder_factory_3)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
20 changes: 10 additions & 10 deletions plansys2_executor/test/unit/executor_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ TEST(executor, action_executor_client)
test_node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE);
aux_node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE);

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(test_node->get_node_base_interface());
exe.add_node(aux_node->get_node_base_interface());
Expand Down Expand Up @@ -314,7 +314,7 @@ TEST(executor, action_executor)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -641,7 +641,7 @@ TEST(executor, action_real_action_1)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -896,7 +896,7 @@ TEST(executor, action_real_action_2)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory4.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory4.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1151,7 +1151,7 @@ TEST(executor, cancel_bt_execution)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1353,7 +1353,7 @@ TEST(executor, executor_client_execute_plan)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1503,7 +1503,7 @@ TEST(executor, executor_client_execute_plan_2)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory4.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory4.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1701,7 +1701,7 @@ TEST(executor, executor_client_ordered_sub_goals)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_charging.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1844,7 +1844,7 @@ TEST(executor, executor_client_cancel_plan)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory3.pddl"});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -1987,7 +1987,7 @@ TEST(executor, action_timeout)
"action_timeouts.move.duration_overrun_percentage", 1.0);
executor_node->set_parameter({"action_timeouts.move.duration_overrun_percentage", 1.0});

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
12 changes: 6 additions & 6 deletions plansys2_executor/test/unit/simple_btbuilder_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ TEST(simple_btbuilder_tests, test_plan_1)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -393,7 +393,7 @@ TEST(simple_btbuilder_tests, test_plan_2)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/factory.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -599,7 +599,7 @@ TEST(simple_btbuilder_tests, test_plan_3)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_2.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_2.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -690,7 +690,7 @@ TEST(simple_btbuilder_tests, test_plan_4)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/cooking_domain.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/cooking_domain.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -807,7 +807,7 @@ TEST(simple_btbuilder_tests, test_plan_5)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/road_trip_domain.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/road_trip_domain.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -919,7 +919,7 @@ TEST(simple_btbuilder_tests, test_plan_6)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/elevator_domain.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/elevator_domain.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
2 changes: 1 addition & 1 deletion plansys2_lifecycle_manager/src/lifecycle_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ int main(int argc, char ** argv)
manager_nodes["executor"] = std::make_shared<plansys2::LifecycleServiceClient>(
"executor_lc_mngr", "executor");

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;
for (auto & manager_node : manager_nodes) {
manager_node.second->init();
exe.add_node(manager_node.second);
Expand Down
4 changes: 2 additions & 2 deletions plansys2_lifecycle_manager/test/lf_manager_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ TEST(lifecycle_manager, lf_client)
auto test_node = rclcpp_lifecycle::LifecycleNode::make_shared("test");
auto client_node = std::make_shared<plansys2::LifecycleServiceClient>("mng_client", "test");

auto exe = rclcpp::executors::SingleThreadedExecutor::make_shared();
auto exe = rclcpp::experimental::executors::EventsExecutor::make_shared();
exe->add_node(test_node->get_node_base_interface());
exe->add_node(client_node->get_node_base_interface());

Expand Down Expand Up @@ -97,7 +97,7 @@ TEST(lifecycle_manager, lf_startup)
manager_nodes["executor"] = std::make_shared<plansys2::LifecycleServiceClient>(
"domain_expert_lc_mngr", "executor");

rclcpp::executors::SingleThreadedExecutor exe;
rclcpp::experimental::executors::EventsExecutor exe;
for (auto & manager_node : manager_nodes) {
manager_node.second->init();
exe.add_node(manager_node.second);
Expand Down
4 changes: 2 additions & 2 deletions plansys2_planner/test/unit/planner_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ TEST(planner_expert, generate_plan_good)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down Expand Up @@ -130,7 +130,7 @@ TEST(planner_expert, generate_plan_with_domain_constants)
domain_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_constants.pddl"});
problem_node->set_parameter({"model_file", pkgpath + "/pddl/domain_simple_constants.pddl"});

rclcpp::executors::MultiThreadedExecutor exe(rclcpp::ExecutorOptions(), 8);
rclcpp::experimental::executors::EventsExecutor exe;

exe.add_node(domain_node->get_node_base_interface());
exe.add_node(problem_node->get_node_base_interface());
Expand Down
Loading
Loading