41 #include <pluginlib/class_list_macros.hpp> 
   46 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"chomp_optimizer");
 
   55   bool initialize(
const moveit::core::RobotModelConstPtr& model, 
const rclcpp::Node::SharedPtr& node,
 
   56                   const std::string& )
 override 
   59     for (
const std::string& 
group : model->getJointModelGroupNames())
 
   63         group, 
group, std::map<std::string, std::string>()
 
   65       pconfig[planner_config_settings.name] = planner_config_settings;
 
   72   planning_interface::PlanningContextPtr
 
   75                      moveit_msgs::msg::MoveItErrorCodes& error_code)
 const override 
   77     error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
   79     if (req.group_name.empty())
 
   81       RCLCPP_ERROR(LOGGER, 
"No group specified to plan for");
 
   82       error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
 
   83       return planning_interface::PlanningContextPtr();
 
   88       RCLCPP_ERROR(LOGGER, 
"No planning scene supplied as input");
 
   89       error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
 
   90       return planning_interface::PlanningContextPtr();
 
   99     context->setPlanningScene(ps);
 
  100     context->setMotionPlanRequest(req);
 
  101     error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
 
std::string getDescription() const override
Get.
 
bool canServiceRequest(const planning_interface::MotionPlanRequest &) const override
Determine whether this plugin instance is able to represent this planning request.
 
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pcs) override
Specify the settings to be used for specific algorithms.
 
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...
 
std::map< std::string, CHOMPPlanningContextPtr > planning_contexts_
 
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &) override
 
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...
 
static CollisionDetectorAllocatorPtr create()
 
Base class for a MoveIt planner.
 
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
 
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.
 
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...