#include <planning_request_adapter.h>
|
| PlanningRequestAdapter () |
|
virtual | ~PlanningRequestAdapter () |
|
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, simply implement as empty. More...
|
|
virtual std::string | getDescription () const |
| Get a short string that identifies the planning request adapter. More...
|
|
bool | adaptAndPlan (const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const |
|
bool | adaptAndPlan (const planning_interface::PlannerManagerPtr &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 |
|
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 response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index. More...
|
|
|
template<typename T > |
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. More...
|
|
Definition at line 51 of file planning_request_adapter.h.
◆ PlannerFn
◆ PlanningRequestAdapter()
planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter |
( |
| ) |
|
|
inline |
◆ ~PlanningRequestAdapter()
virtual planning_request_adapter::PlanningRequestAdapter::~PlanningRequestAdapter |
( |
| ) |
|
|
inlinevirtual |
◆ adaptAndPlan() [1/3]
Adapt the planning request if needed, call the planner function planner and update the planning response if needed. If the response is changed, the index values of the states added without planning are added to added_path_index.
Implemented in chomp::OptimizerAdapter, default_planner_request_adapters::FixStartStatePathConstraints, default_planner_request_adapters::FixStartStateCollision, default_planner_request_adapters::FixStartStateBounds, default_planner_request_adapters::ResolveConstraintFrames, default_planner_request_adapters::FixWorkspaceBounds, default_planner_request_adapters::Empty, default_planner_request_adapters::AddTimeParameterization, default_planner_request_adapters::AddTimeOptimalParameterization, default_planner_request_adapters::AddRuckigTrajectorySmoothing, and default_planner_request_adapters::AddIterativeSplineParameterization.
◆ adaptAndPlan() [2/3]
◆ adaptAndPlan() [3/3]
◆ getDescription()
virtual std::string planning_request_adapter::PlanningRequestAdapter::getDescription |
( |
| ) |
const |
|
inlinevirtual |
Get a short string that identifies the planning request adapter.
Reimplemented in default_planner_request_adapters::ResolveConstraintFrames, default_planner_request_adapters::FixWorkspaceBounds, default_planner_request_adapters::FixStartStatePathConstraints, default_planner_request_adapters::FixStartStateCollision, default_planner_request_adapters::FixStartStateBounds, default_planner_request_adapters::Empty, default_planner_request_adapters::AddTimeParameterization, default_planner_request_adapters::AddTimeOptimalParameterization, default_planner_request_adapters::AddRuckigTrajectorySmoothing, default_planner_request_adapters::AddIterativeSplineParameterization, and chomp::OptimizerAdapter.
Definition at line 71 of file planning_request_adapter.h.
◆ getParam()
template<typename T >
T planning_request_adapter::PlanningRequestAdapter::getParam |
( |
const rclcpp::Node::SharedPtr & |
node, |
|
|
const rclcpp::Logger & |
logger, |
|
|
const std::string & |
parameter_namespace, |
|
|
const std::string & |
parameter_name, |
|
|
T |
default_value = {} |
|
) |
| const |
|
inlineprotected |
◆ initialize()
virtual void planning_request_adapter::PlanningRequestAdapter::initialize |
( |
const rclcpp::Node::SharedPtr & |
node, |
|
|
const std::string & |
parameter_namespace |
|
) |
| |
|
pure virtual |
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed, simply implement as empty.
Implemented in default_planner_request_adapters::FixWorkspaceBounds, default_planner_request_adapters::FixStartStateCollision, default_planner_request_adapters::FixStartStateBounds, default_planner_request_adapters::AddTimeOptimalParameterization, chomp::OptimizerAdapter, default_planner_request_adapters::ResolveConstraintFrames, default_planner_request_adapters::FixStartStatePathConstraints, default_planner_request_adapters::Empty, default_planner_request_adapters::AddTimeParameterization, default_planner_request_adapters::AddRuckigTrajectorySmoothing, and default_planner_request_adapters::AddIterativeSplineParameterization.
The documentation for this class was generated from the following files: