42#include <ompl/util/Console.h>
59 class OutputHandler :
public ompl::msg::OutputHandler
62 void log(
const std::string& text, ompl::msg::LogLevel level,
const char* filename,
int line)
override
66 case ompl::msg::LOG_DEV2:
67 case ompl::msg::LOG_DEV1:
68 case ompl::msg::LOG_DEBUG:
69 case ompl::msg::LOG_INFO:
71 RCLCPP_DEBUG(getLogger(),
"%s:%i - %s", filename, line, text.c_str());
73 case ompl::msg::LOG_WARN:
74 RCLCPP_WARN(getLogger(),
"%s:%i - %s", filename, line, text.c_str());
76 case ompl::msg::LOG_ERROR:
77 RCLCPP_ERROR(getLogger(),
"%s:%i - %s", filename, line, text.c_str());
79 case ompl::msg::LOG_NONE:
87 output_handler_ = std::make_shared<OutputHandler>();
88 ompl::msg::useOutputHandler(output_handler_.get());
91 bool initialize(
const moveit::core::RobotModelConstPtr& model,
const rclcpp::Node::SharedPtr& node,
92 const std::string& parameter_namespace)
override
94 ompl_interface_ = std::make_unique<OMPLInterface>(model, node, parameter_namespace);
101 return req.trajectory_constraints.constraints.empty();
113 algs.reserve(pconfig.size());
114 for (
const std::pair<const std::string, planning_interface::PlannerConfigurationSettings>& config : pconfig)
115 algs.push_back(config.first);
121 ompl_interface_->setPlannerConfigurations(pconfig);
123 PlannerManager::setPlannerConfigurations(ompl_interface_->getPlannerConfigurations());
126 planning_interface::PlanningContextPtr
129 moveit_msgs::msg::MoveItErrorCodes& error_code)
const override
131 return ompl_interface_->getPlanningContext(
planning_scene, req, error_code);
135 rclcpp::Node::SharedPtr node_;
136 std::unique_ptr<OMPLInterface> ompl_interface_;
137 std::shared_ptr<ompl::msg::OutputHandler> output_handler_;
142#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 a short string that identifies the planning interface.
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.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.