Skip to content

Commit

Permalink
Make sure that pipeline does not abort if no request adapter is confi…
Browse files Browse the repository at this point in the history
…gured
  • Loading branch information
sjahr committed Oct 23, 2023
1 parent 9a58b30 commit ca23615
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

#include <moveit/macros/class_forward.h>
#include <moveit/planning_interface/planning_interface.h>
#include <functional>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,7 @@ void loadPluginVector(const std::shared_ptr<rclcpp::Node>& node,
};

} // namespace

/** \brief This class facilitates loading planning plugins and planning adapter plugins. It implements functionality to
* use the loaded plugins in a motion planning pipeline consisting of PlanningRequestAdapters (Pre-processing), a
* Planner plugin and PlanningResponseAdapters (Post-processing).*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -219,6 +219,7 @@ bool planning_pipeline::PlanningPipeline::generatePlan(const planning_scene::Pla
}
else
{
solved = true;
RCLCPP_INFO(LOGGER, "No PlanningRequestAdapters to apply pipeline '%s'.", parameter_namespace_.c_str());
}

Expand Down

0 comments on commit ca23615

Please sign in to comment.