43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
68 virtual void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace) = 0;
76 bool adaptAndPlan(
const planning_interface::PlannerManagerPtr& planner,
81 bool adaptAndPlan(
const planning_interface::PlannerManagerPtr& planner,
84 std::vector<std::size_t>& added_path_index)
const;
94 std::vector<std::size_t>& added_path_index)
const = 0;
99 T
getParam(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Logger& logger,
const std::string& parameter_namespace,
100 const std::string& parameter_name, T default_value = {})
const
102 std::string full_name = parameter_namespace.empty() ? parameter_name : parameter_namespace +
"." + parameter_name;
104 if (!node->get_parameter(full_name, value))
106 RCLCPP_INFO(logger,
"Param '%s' was not set. Using default value: %s", full_name.c_str(),
107 std::to_string(default_value).c_str());
108 return default_value;
112 RCLCPP_INFO(logger,
"Param '%s' was set to %s", full_name.c_str(), std::to_string(value).c_str());
126 void addAdapter(
const PlanningRequestAdapterConstPtr& adapter)
128 adapters_.push_back(adapter);
131 bool adaptAndPlan(
const planning_interface::PlannerManagerPtr& planner,
136 bool adaptAndPlan(
const planning_interface::PlannerManagerPtr& planner,
139 std::vector<std::size_t>& added_path_index)
const;
142 std::vector<PlanningRequestAdapterConstPtr> adapters_;
Apply a sequence of adapters to a motion plan.
PlanningRequestAdapterChain()
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
void addAdapter(const PlanningRequestAdapterConstPtr &adapter)
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const =0
Adapt the planning request if needed, call the planner function planner and update the planning respo...
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string ¶meter_namespace, const std::string ¶meter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
virtual std::string getDescription() const
Get a short string that identifies the planning request adapter.
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
virtual void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)=0
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
virtual ~PlanningRequestAdapter()
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Generic interface to adapting motion planning requests.
MOVEIT_CLASS_FORWARD(PlanningRequestAdapter)
This namespace includes the central class for representing planning contexts.