41 #include <ompl/util/Console.h> 
   45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.ompl_planner_manager");
 
   46 static const rclcpp::Logger OMPL_LOGGER = rclcpp::get_logger(
"ompl");
 
   53     class OutputHandler : 
public ompl::msg::OutputHandler
 
   56       void log(
const std::string& 
text, ompl::msg::LogLevel level, 
const char* filename, 
int line)
 override 
   60           case ompl::msg::LOG_DEV2:
 
   61           case ompl::msg::LOG_DEV1:
 
   62           case ompl::msg::LOG_DEBUG:
 
   63           case ompl::msg::LOG_INFO:
 
   65             RCLCPP_DEBUG(OMPL_LOGGER, 
"%s:%i - %s", filename, line, 
text.c_str());
 
   67           case ompl::msg::LOG_WARN:
 
   68             RCLCPP_WARN(OMPL_LOGGER, 
"%s:%i - %s", filename, line, 
text.c_str());
 
   70           case ompl::msg::LOG_ERROR:
 
   71             RCLCPP_ERROR(OMPL_LOGGER, 
"%s:%i - %s", filename, line, 
text.c_str());
 
   73           case ompl::msg::LOG_NONE:
 
   81     output_handler_ = std::make_shared<OutputHandler>();
 
   82     ompl::msg::useOutputHandler(output_handler_.get());
 
   85   bool initialize(
const moveit::core::RobotModelConstPtr& model, 
const rclcpp::Node::SharedPtr& node,
 
   86                   const std::string& parameter_namespace)
 override 
   88     ompl_interface_ = std::make_unique<OMPLInterface>(model, node, parameter_namespace);
 
   95     return req.trajectory_constraints.constraints.empty();
 
  107     algs.reserve(pconfig.size());
 
  108     for (
const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
 
  109       algs.push_back(config.first);
 
  115     ompl_interface_->setPlannerConfigurations(pconfig);
 
  117     PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
 
  120   planning_interface::PlanningContextPtr
 
  123                      moveit_msgs::msg::MoveItErrorCodes& error_code)
 const override 
  125     return ompl_interface_->getPlanningContext(
planning_scene, req, error_code);
 
  129   rclcpp::Node::SharedPtr node_;
 
  130   std::unique_ptr<OMPLInterface> ompl_interface_;
 
  131   std::shared_ptr<ompl::msg::OutputHandler> output_handler_;
 
  136 #include <pluginlib/class_list_macros.hpp> 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
 
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig) override
Specify the settings to be used for specific algorithms.
 
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Construct a planning context given the current scene and a planning request. If a problem is encounte...
 
std::string getDescription() const override
Get.
 
bool canServiceRequest(const moveit_msgs::msg::MotionPlanRequest &req) const override
Determine whether this plugin instance is able to represent this planning request.
 
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
 
void getPlanningAlgorithms(std::vector< std::string > &algs) const override
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
 
Base class for a MoveIt planner.
 
The MoveIt interface to OMPL.
 
This namespace includes the base class for MoveIt planners.
 
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
 
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
 
This namespace includes the central class for representing planning contexts.