moveit2
The MoveIt Motion Planning Framework for ROS 2.
Functions
moveit_py::bind_planning_component Namespace Reference

Functions

planning_interface::MotionPlanResponse plan (std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
 
bool setGoal (std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::optional< std::string > configuration_name, std::optional< moveit::core::RobotState > robot_state, std::optional< geometry_msgs::msg::PoseStamped > pose_stamped_msg, std::optional< std::string > pose_link, std::optional< std::vector< moveit_msgs::msg::Constraints >> motion_plan_constraints)
 
bool setStartState (std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::optional< std::string > configuration_name, std::optional< moveit::core::RobotState > robot_state)
 
void initPlanRequestParameters (py::module &m)
 
void initMultiPlanRequestParameters (py::module &m)
 
void initPlanningComponent (py::module &m)
 

Function Documentation

◆ initMultiPlanRequestParameters()

void moveit_py::bind_planning_component::initMultiPlanRequestParameters ( py::module &  m)

Definition at line 224 of file planning_component.cpp.

Here is the caller graph for this function:

◆ initPlanningComponent()

void moveit_py::bind_planning_component::initPlanningComponent ( py::module &  m)

Definition at line 239 of file planning_component.cpp.

Here is the caller graph for this function:

◆ initPlanRequestParameters()

void moveit_py::bind_planning_component::initPlanRequestParameters ( py::module &  m)

Definition at line 197 of file planning_component.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ plan()

planning_interface::MotionPlanResponse moveit_py::bind_planning_component::plan ( std::shared_ptr< moveit_cpp::PlanningComponent > &  planning_component,
std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &  single_plan_parameters,
std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &  multi_plan_parameters,
std::shared_ptr< planning_scene::PlanningScene > &  planning_scene,
std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction solution_selection_function,
std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction stopping_criterion_callback 
)

Definition at line 45 of file planning_component.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setGoal()

bool moveit_py::bind_planning_component::setGoal ( std::shared_ptr< moveit_cpp::PlanningComponent > &  planning_component,
std::optional< std::string >  configuration_name,
std::optional< moveit::core::RobotState robot_state,
std::optional< geometry_msgs::msg::PoseStamped >  pose_stamped_msg,
std::optional< std::string >  pose_link,
std::optional< std::vector< moveit_msgs::msg::Constraints >>  motion_plan_constraints 
)

Definition at line 107 of file planning_component.cpp.

◆ setStartState()

bool moveit_py::bind_planning_component::setStartState ( std::shared_ptr< moveit_cpp::PlanningComponent > &  planning_component,
std::optional< std::string >  configuration_name,
std::optional< moveit::core::RobotState robot_state 
)

Definition at line 170 of file planning_component.cpp.