moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Public Member Functions | |
FixStartStatePathConstraints () | |
void | initialize (const rclcpp::Node::SharedPtr &, const std::string &) 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... | |
Public Member Functions inherited from planning_request_adapter::PlanningRequestAdapter | |
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 |
Additional Inherited Members | |
Public Types inherited from planning_request_adapter::PlanningRequestAdapter | |
using | PlannerFn = std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> |
Protected Member Functions inherited from planning_request_adapter::PlanningRequestAdapter | |
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 50 of file fix_start_state_path_constraints.cpp.
|
inline |
Definition at line 53 of file fix_start_state_path_constraints.cpp.
|
inlineoverridevirtual |
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.
Implements planning_request_adapter::PlanningRequestAdapter.
Definition at line 66 of file fix_start_state_path_constraints.cpp.
|
inlineoverridevirtual |
Get a short string that identifies the planning request adapter.
Reimplemented from planning_request_adapter::PlanningRequestAdapter.
Definition at line 61 of file fix_start_state_path_constraints.cpp.
|
inlineoverridevirtual |
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed, simply implement as empty.
Implements planning_request_adapter::PlanningRequestAdapter.
Definition at line 57 of file fix_start_state_path_constraints.cpp.