45 static const rclcpp::Logger LOGGER =
rclcpp::get_logger(
"moveit.ompl_planning.ompl_interface");
48 const std::string& parameter_namespace)
50 , parameter_namespace_(parameter_namespace)
51 , robot_model_(robot_model)
52 , constraint_sampler_manager_(std::make_shared<
constraint_samplers::ConstraintSamplerManager>())
53 , context_manager_(robot_model, constraint_sampler_manager_)
54 , use_constraints_approximations_(true)
56 RCLCPP_DEBUG(LOGGER,
"Initializing OMPL interface using ROS parameters");
63 const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
65 , parameter_namespace_(parameter_namespace)
66 , robot_model_(robot_model)
67 , constraint_sampler_manager_(std::make_shared<
constraint_samplers::ConstraintSamplerManager>())
68 , context_manager_(robot_model, constraint_sampler_manager_)
69 , use_constraints_approximations_(true)
71 RCLCPP_DEBUG(LOGGER,
"Initializing OMPL interface using specified configuration");
85 if (pconfig.find(
group->getName()) == pconfig.end())
89 pconfig2[empty.
name] = empty;
96 ModelBasedPlanningContextPtr
100 moveit_msgs::msg::MoveItErrorCodes dummy;
104 ModelBasedPlanningContextPtr
107 moveit_msgs::msg::MoveItErrorCodes& error_code)
const
109 ModelBasedPlanningContextPtr ctx =
116 constraint_sampler_manager_loader_ =
117 std::make_shared<constraint_sampler_manager_loader::ConstraintSamplerManagerLoader>(
node_,
122 const std::map<std::string, std::string>& group_params,
125 rcl_interfaces::msg::ListParametersResult planner_params_result =
128 if (planner_params_result.names.empty())
130 RCLCPP_ERROR(LOGGER,
"Could not find the planner configuration '%s' on the param server", planner_id.c_str());
134 planner_config.
name = group_name +
"[" + planner_id +
"]";
135 planner_config.
group = group_name;
138 planner_config.
config = group_params;
141 for (
const auto& planner_param : planner_params_result.names)
143 const rclcpp::Parameter param =
node_->get_parameter(planner_param);
144 auto param_name = planner_param.substr(planner_param.find(planner_id) + planner_id.size() + 1);
145 planner_config.
config[param_name] = param.value_to_string();
157 for (
const std::string& group_name :
robot_model_->getJointModelGroupNames())
161 static const std::pair<std::string, rclcpp::ParameterType> KNOWN_GROUP_PARAMS[] = {
162 {
"projection_evaluator", rclcpp::ParameterType::PARAMETER_STRING },
163 {
"longest_valid_segment_fraction", rclcpp::ParameterType::PARAMETER_DOUBLE },
164 {
"enforce_joint_model_state_space", rclcpp::ParameterType::PARAMETER_BOOL },
165 {
"enforce_constrained_state_space", rclcpp::ParameterType::PARAMETER_BOOL }
171 std::map<std::string, std::string> specific_group_params;
172 for (
const auto& [
name, type] : KNOWN_GROUP_PARAMS)
174 std::string param_name{ group_name_param };
177 if (
node_->has_parameter(param_name))
179 const rclcpp::Parameter parameter =
node_->get_parameter(param_name);
180 if (parameter.get_type() != type)
182 RCLCPP_ERROR_STREAM(LOGGER,
"Invalid type for parameter '" <<
name <<
"' expected ["
183 << rclcpp::to_string(type) <<
"] got ["
184 << rclcpp::to_string(parameter.get_type()) <<
']');
187 if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
189 specific_group_params[
name] = parameter.as_string();
191 else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE)
195 else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
197 specific_group_params[
name] = std::to_string(parameter.as_int());
199 else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_BOOL)
201 specific_group_params[
name] = std::to_string(parameter.as_bool());
208 std::string default_planner_id;
209 if (
node_->get_parameter(group_name_param +
".default_planner_config", default_planner_id))
213 default_planner_id =
"";
217 if (default_planner_id.empty())
219 default_pc.
group = group_name;
220 default_pc.
config = specific_group_params;
221 default_pc.
config[
"type"] =
"geometric::RRTConnect";
224 default_pc.
name = group_name;
225 pconfig[default_pc.
name] = default_pc;
228 std::vector<std::string> config_names;
229 if (
node_->get_parameter(group_name_param +
".planner_configs", config_names))
231 for (
const auto& planner_id : config_names)
236 pconfig[pc.
name] = pc;
242 for (
const auto& [
name, config_settings] : pconfig)
244 RCLCPP_DEBUG(LOGGER,
"Parameters for configuration '%s'",
name.c_str());
246 for (
const auto& [param_name, param_value] : config_settings.config)
248 RCLCPP_DEBUG_STREAM(LOGGER,
" - " << param_name <<
" = " << param_value);
257 RCLCPP_INFO(LOGGER,
"OMPL ROS interface is running.");
rclcpp::Node::SharedPtr node_
bool use_constraints_approximations_
void printStatus()
Print the status of this node.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
PlanningContextManager context_manager_
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.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
const std::string parameter_namespace_
The ROS node.
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
void loadPlannerConfigurations()
Configure the planners.
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
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.
locale-agnostic conversion functions from floating point numbers to strings
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
std::string toString(double d)
Convert a double to std::string using the classic C locale.
rclcpp::Logger get_logger()
The MoveIt interface to OMPL.
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 ...
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
std::string group
The group (as defined in the SRDF) this configuration is meant for.