|
void | initialize (const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override |
| Initialize parameters using the passed Node and parameter namespace. If no initialization is needed, simply implement as empty. More...
|
|
std::string | getDescription () const override |
| Get a short string that identifies the planning request adapter. More...
|
|
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 override |
| 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...
|
|
| PlanningRequestAdapter () |
|
virtual | ~PlanningRequestAdapter () |
|
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 |
|
◆ adaptAndPlan()
◆ getDescription()
std::string default_planner_request_adapters::FixStartStateCollision::getDescription |
( |
| ) |
const |
|
inlineoverridevirtual |
◆ initialize()
void default_planner_request_adapters::FixStartStateCollision::initialize |
( |
const rclcpp::Node::SharedPtr & |
node, |
|
|
const std::string & |
parameter_namespace |
|
) |
| |
|
inlineoverridevirtual |
◆ ATTEMPTS_PARAM_NAME
const std::string default_planner_request_adapters::FixStartStateCollision::ATTEMPTS_PARAM_NAME = "max_sampling_attempts" |
|
static |
◆ DT_PARAM_NAME
const std::string default_planner_request_adapters::FixStartStateCollision::DT_PARAM_NAME = "start_state_max_dt" |
|
static |
◆ JIGGLE_PARAM_NAME
const std::string default_planner_request_adapters::FixStartStateCollision::JIGGLE_PARAM_NAME = "jiggle_fraction" |
|
static |
The documentation for this class was generated from the following file: