Skip to content

Commit

Permalink
Lintering
Browse files Browse the repository at this point in the history
Signed-off-by: Francisco Martín Rico <[email protected]>
  • Loading branch information
fmrico committed Jan 14, 2025
1 parent 733f13c commit 08d2ee7
Show file tree
Hide file tree
Showing 7 changed files with 37 additions and 48 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <optional>
#include <string>
#include <memory>
#include <list>
#include <vector>

#include "plansys2_msgs/action/execute_plan.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ class ExecutorNode : public rclcpp_lifecycle::LifecycleNode
rclcpp_action::CancelResponse handle_cancel(
const std::shared_ptr<GoalHandleExecutePlan> goal_handle);
void handle_accepted(const std::shared_ptr<GoalHandleExecutePlan> goal_handle);

std::list<std::shared_ptr<GoalHandleExecutePlan>> goal_handlers_;

std::vector<plansys2_msgs::msg::ActionExecutionInfo> get_feedback_info(
Expand Down
2 changes: 1 addition & 1 deletion plansys2_executor/src/plansys2_executor/ExecutorNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -706,7 +706,7 @@ ExecutorNode::handle_accepted(const std::shared_ptr<GoalHandleExecutePlan> goal_
auto result = std::make_shared<ExecutePlan::Result>();
result->result = plansys2_msgs::action::ExecutePlan::Result::FAILURE;
goal_handlers_.back()->succeed(result);

goal_handlers_.push_back(goal_handle);
replan_requested_ = true;
}
Expand Down
47 changes: 18 additions & 29 deletions plansys2_planner/src/plansys2_planner/PlannerNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,11 @@ PlannerNode::~PlannerNode()

for (const auto & library : loaded_libraries) {
try {
lp_loader_.unloadLibraryForClass(library);
std::cout << "Successfully unloaded library: " << library << std::endl;
lp_loader_.unloadLibraryForClass(library);
std::cout << "Successfully unloaded library: " << library << std::endl;
} catch (const pluginlib::LibraryUnloadException & e) {
std::cerr << "Failed to unload library: " << library << ". Error: " << e.what() << std::endl;
std::cerr << "Failed to unload library: " << library <<
". Error: " << e.what() << std::endl;
}
}
}
Expand Down Expand Up @@ -85,9 +86,7 @@ PlannerNode::on_configure(const rclcpp_lifecycle::State & state)
plansys2::PlanSolverBase::Ptr solver =
lp_loader_.createUniqueInstance(solver_types_[i]);

std::cerr << "====================== 1 " << std::endl;
solver->configure(node, solver_ids_[i]);
std::cerr << "====================== 2 " << std::endl;

RCLCPP_INFO(
get_logger(), "Created solver : %s of type %s",
Expand Down Expand Up @@ -183,15 +182,12 @@ PlannerNode::get_plan_service_callback(
const std::shared_ptr<plansys2_msgs::srv::GetPlan::Request> request,
const std::shared_ptr<plansys2_msgs::srv::GetPlan::Response> response)
{
std::cerr << "get_plan_array_service_callback 1" << std::endl;
std::map<std::string, std::future<std::optional<plansys2_msgs::msg::Plan>>> futures;
std::map<std::string, std::optional<plansys2_msgs::msg::Plan>> results;

for (auto & solver : solvers_) {
std::cerr << "get_plan_array_service_callback future for " << solver.first << std::endl;

futures[solver.first] = std::async(std::launch::async,
&plansys2::PlanSolverBase::getPlan,solver.second,
&plansys2::PlanSolverBase::getPlan, solver.second,
request->domain, request->problem, get_namespace(), solver_timeout_);
}

Expand All @@ -202,23 +198,21 @@ PlannerNode::get_plan_service_callback(
for (auto & fut : futures) {
if (results.find(fut.first) == results.end()) {
if (fut.second.wait_for(std::chrono::seconds(0)) == std::future_status::ready) {
std::cerr << "get_plan_array_service_callback result ready for " << fut.first << std::endl;
results[fut.first] = fut.second.get();
pending_result--;
}
}
}
}

// Destroying unfinished futures
for (auto & fut : futures) {
if (results.find(fut.first) == results.end()) {
std::cerr << "Destroying unfinished future for " << fut.first << std::endl;
try {
// Retrieve and discard the result to avoid blocking in destructor
fut.second.get();
} catch (const std::exception &e) {
std::cerr << "Exception while destroying future for " << fut.first << ": " << e.what() << std::endl;
} catch (const std::exception & e) {
RCLCPP_WARN_STREAM(
get_logger(), "Exception while destroying future for "
<< fut.first << ": " << e.what());
}
}
}
Expand All @@ -227,18 +221,17 @@ PlannerNode::get_plan_service_callback(
bool anyplan = false;
for (auto & result : results) {
if (result.second.has_value()) {
plans.push_back(result.second.value());
plans.push_back(result.second.value());
anyplan = true;
}
}

std::sort(plans.begin(), plans.end(),
[](const plansys2_msgs::msg::Plan & a, const plansys2_msgs::msg::Plan & b)
{
return a.items.size() < b.items.size();
{
return a.items.size() < b.items.size();
});

std::cerr << "get_plan_array_service_callback end" << std::endl;
if (anyplan) {
response->success = true;
response->plan = plans.front();
Expand All @@ -254,15 +247,12 @@ PlannerNode::get_plan_array_service_callback(
const std::shared_ptr<plansys2_msgs::srv::GetPlanArray::Request> request,
const std::shared_ptr<plansys2_msgs::srv::GetPlanArray::Response> response)
{
std::cerr << "get_plan_array_service_callback 1" << std::endl;
std::map<std::string, std::future<std::optional<plansys2_msgs::msg::Plan>>> futures;
std::map<std::string, std::optional<plansys2_msgs::msg::Plan>> results;

for (auto & solver : solvers_) {
std::cerr << "get_plan_array_service_callback future for " << solver.first << std::endl;

futures[solver.first] = std::async(std::launch::async,
&plansys2::PlanSolverBase::getPlan,solver.second,
&plansys2::PlanSolverBase::getPlan, solver.second,
request->domain, request->problem, get_namespace(), solver_timeout_);
}

Expand All @@ -273,7 +263,6 @@ PlannerNode::get_plan_array_service_callback(
for (auto & fut : futures) {
if (results.find(fut.first) == results.end()) {
if (fut.second.wait_for(std::chrono::seconds(0)) == std::future_status::ready) {
std::cerr << "get_plan_array_service_callback result ready for " << fut.first << std::endl;
results[fut.first] = fut.second.get();
pending_result--;
}
Expand All @@ -284,25 +273,25 @@ PlannerNode::get_plan_array_service_callback(
// Destroying unfinished futures
for (auto & fut : futures) {
if (results.find(fut.first) == results.end()) {
std::cerr << "Destroying unfinished future for " << fut.first << std::endl;
try {
// Retrieve and discard the result to avoid blocking in destructor
fut.second.get();
} catch (const std::exception &e) {
std::cerr << "Exception while destroying future for " << fut.first << ": " << e.what() << std::endl;
} catch (const std::exception & e) {
RCLCPP_WARN_STREAM(
get_logger(), "Exception while destroying future for "
<< fut.first << ": " << e.what());
}
}
}

bool anyplan = false;
for (auto & result : results) {
if (result.second.has_value()) {
response->plan_array.plan_array.push_back(result.second.value());
response->plan_array.plan_array.push_back(result.second.value());
anyplan = true;
}
}

std::cerr << "get_plan_array_service_callback end" << std::endl;
if (anyplan) {
response->success = true;
} else {
Expand Down
30 changes: 16 additions & 14 deletions plansys2_planner/test/unit/planner_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,13 +134,13 @@ TEST(planner_expert, generate_plan_with_args)
planner_node->set_parameter({"plan_solver_plugins", solver_plugins});

plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.plugin",
planner_node, "POPF1.plugin",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.arguments",
planner_node, "POPF1.arguments",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.output_dir",
planner_node, "POPF1.output_dir",
rclcpp::ParameterValue(std::string()));

planner_node->set_parameter({"POPF1.plugin", "plansys2/POPFPlanSolver"});
Expand Down Expand Up @@ -230,31 +230,31 @@ TEST(planner_expert, generate_plans)
planner_node->set_parameter({"plan_solver_plugins", solver_plugins});

plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.plugin",
planner_node, "POPF1.plugin",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.arguments",
planner_node, "POPF1.arguments",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF1.output_dir",
planner_node, "POPF1.output_dir",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF2.plugin",
planner_node, "POPF2.plugin",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF2.arguments",
planner_node, "POPF2.arguments",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "POPF2.output_dir",
planner_node, "POPF2.output_dir",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "OPTICS.plugin",
planner_node, "OPTICS.plugin",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "OPTICS.arguments",
planner_node, "OPTICS.arguments",
rclcpp::ParameterValue(std::string()));
plansys2::declare_parameter_if_not_declared(
planner_node, "OPTICS.output_dir",
planner_node, "OPTICS.output_dir",
rclcpp::ParameterValue(std::string()));

planner_node->set_parameter({"POPF1.plugin", "plansys2/POPFPlanSolver"});
Expand Down Expand Up @@ -319,12 +319,14 @@ TEST(planner_expert, generate_plans)
ASSERT_TRUE(
problem_client->setGoal(plansys2::Goal("(and (robot_talk leia message1 francisco))")));

auto plans_bad = planner_client->getPlanArray(domain_client->getDomain(), problem_client->getProblem());
auto plans_bad = planner_client->getPlanArray(
domain_client->getDomain(), problem_client->getProblem());
ASSERT_TRUE(plans_bad.plan_array.empty());

ASSERT_TRUE(problem_client->addPredicate(plansys2::Predicate(predicates[1])));

auto plans_good = planner_client->getPlanArray(domain_client->getDomain(), problem_client->getProblem());
auto plans_good = planner_client->getPlanArray(
domain_client->getDomain(), problem_client->getProblem());
ASSERT_EQ(3u, plans_good.plan_array.size());

finish = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -588,8 +588,6 @@ ProblemExpertNode::get_problem_service_callback(
} else {
response->success = true;
response->problem = problem_expert_->getProblem();

std::cerr << "get_problem_service_callback [" << response->problem << "]" << std::endl;
}
}

Expand Down
1 change: 0 additions & 1 deletion plansys2_terminal/src/plansys2_terminal/Terminal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -904,7 +904,6 @@ Terminal::execute_action(std::vector<std::string> & command)

complete_action.pop_back();

std::cerr << "<[" << complete_action << "]" << std::endl;
plansys2_msgs::msg::PlanItem action;
action.time = 0.0;
action.action = complete_action;
Expand Down

0 comments on commit 08d2ee7

Please sign in to comment.