moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <pybind11/pybind11.h>
#include <pybind11/eigen.h>
#include <pybind11/stl.h>
#include <pybind11/numpy.h>
#include <pybind11/functional.h>
#include <moveit_py/moveit_py_utils/copy_ros_msg.h>
#include <moveit_py/moveit_py_utils/ros_msg_typecasters.h>
#include <moveit/moveit_cpp/moveit_cpp.h>
#include <moveit/moveit_cpp/planning_component.h>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <moveit_msgs/msg/constraints.hpp>
#include "moveit_cpp.h"
#include "../planning_scene_monitor/planning_scene_monitor.h"
#include "../../moveit_core/planning_interface/planning_response.h"
Go to the source code of this file.
Namespaces | |
namespace | moveit_py |
namespace | moveit_py::bind_planning_component |
Functions | |
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) |
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) |
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) |
void | moveit_py::bind_planning_component::initPlanRequestParameters (py::module &m) |
void | moveit_py::bind_planning_component::initMultiPlanRequestParameters (py::module &m) |
void | moveit_py::bind_planning_component::initPlanningComponent (py::module &m) |