55                             const std::string& parameter_namespace)
 
   57  , parameter_namespace_(parameter_namespace)
 
   58  , robot_model_(robot_model)
 
   59  , constraint_sampler_manager_(std::make_shared<
constraint_samplers::ConstraintSamplerManager>())
 
   60  , context_manager_(robot_model, constraint_sampler_manager_)
 
   61  , use_constraints_approximations_(true)
 
   63  RCLCPP_DEBUG(getLogger(), 
"Initializing OMPL interface using ROS parameters");
 
 
   70                             const rclcpp::Node::SharedPtr& node, 
const std::string& parameter_namespace)
 
   72  , parameter_namespace_(parameter_namespace)
 
   73  , robot_model_(robot_model)
 
   74  , constraint_sampler_manager_(std::make_shared<
constraint_samplers::ConstraintSamplerManager>())
 
   75  , context_manager_(robot_model, constraint_sampler_manager_)
 
   76  , use_constraints_approximations_(true)
 
   78  RCLCPP_DEBUG(getLogger(), 
"Initializing OMPL interface using specified configuration");
 
 
  129                                             const std::map<std::string, std::string>& group_params,
 
  132  rcl_interfaces::msg::ListParametersResult planner_params_result =
 
  135  if (planner_params_result.names.empty())
 
  137    RCLCPP_ERROR(getLogger(), 
"Could not find the planner configuration '%s' on the param server", planner_id.c_str());
 
  141  planner_config.
name = group_name + 
"[" + planner_id + 
"]";
 
  142  planner_config.
group = group_name;
 
  145  planner_config.
config = group_params;
 
  148  for (
const auto& planner_param : planner_params_result.names)
 
  150    const rclcpp::Parameter param = 
node_->get_parameter(planner_param);
 
  151    auto param_name = planner_param.substr(planner_param.find(planner_id) + planner_id.size() + 1);
 
  152    planner_config.
config[param_name] = param.value_to_string();
 
 
  164  for (
const std::string& group_name : 
robot_model_->getJointModelGroupNames())
 
  168    static const std::pair<std::string, rclcpp::ParameterType> KNOWN_GROUP_PARAMS[] = {
 
  169      { 
"projection_evaluator", rclcpp::ParameterType::PARAMETER_STRING },
 
  170      { 
"longest_valid_segment_fraction", rclcpp::ParameterType::PARAMETER_DOUBLE },
 
  171      { 
"enforce_joint_model_state_space", rclcpp::ParameterType::PARAMETER_BOOL },
 
  172      { 
"enforce_constrained_state_space", rclcpp::ParameterType::PARAMETER_BOOL }
 
  178    std::map<std::string, std::string> specific_group_params;
 
  179    for (
const auto& [name, type] : KNOWN_GROUP_PARAMS)
 
  181      std::string param_name{ group_name_param };
 
  184      if (
node_->has_parameter(param_name))
 
  186        const rclcpp::Parameter parameter = 
node_->get_parameter(param_name);
 
  187        if (parameter.get_type() != type)
 
  189          RCLCPP_ERROR_STREAM(getLogger(), 
"Invalid type for parameter '" 
  190                                               << name << 
"' expected [" << rclcpp::to_string(type) << 
"] got [" 
  191                                               << rclcpp::to_string(parameter.get_type()) << 
']');
 
  194        if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
 
  196          specific_group_params[name] = parameter.as_string();
 
  198        else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE)
 
  202        else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
 
  204          specific_group_params[name] = std::to_string(parameter.as_int());
 
  206        else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_BOOL)
 
  208          specific_group_params[name] = std::to_string(parameter.as_bool());
 
  215    std::string default_planner_id;
 
  216    if (
node_->get_parameter(group_name_param + 
".default_planner_config", default_planner_id))
 
  220        default_planner_id = 
"";
 
  224    if (default_planner_id.empty())
 
  226      default_pc.
group = group_name;
 
  227      default_pc.
config = specific_group_params;
 
  228      default_pc.
config[
"type"] = 
"geometric::RRTConnect";
 
  231    default_pc.
name = group_name;  
 
  232    pconfig[default_pc.
name] = default_pc;
 
  235    std::vector<std::string> config_names;
 
  236    if (
node_->get_parameter(group_name_param + 
".planner_configs", config_names))
 
  238      for (
const auto& planner_id : config_names)
 
  243          pconfig[pc.
name] = pc;
 
  249  for (
const auto& [name, config_settings] : pconfig)
 
  251    RCLCPP_DEBUG(getLogger(), 
"Parameters for configuration '%s'", name.c_str());
 
  253    for (
const auto& [param_name, param_value] : config_settings.config)
 
  255      RCLCPP_DEBUG_STREAM(getLogger(), 
" - " << param_name << 
" = " << param_value);
 
 
bool loadPlannerConfiguration(const std::string &group_name, const std::string &planner_id, const std::map< std::string, std::string > &group_params, planning_interface::PlannerConfigurationSettings &planner_config)
Load planner configurations for specified group into planner_config.
 
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code, const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
 
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.