39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
63ActiveContexts& getActiveContexts()
65 static ActiveContexts s_ac;
72 ActiveContexts& ac = getActiveContexts();
73 std::scoped_lock _(ac.mutex_);
74 ac.contexts_.insert(
this);
79 ActiveContexts& ac = getActiveContexts();
80 std::scoped_lock _(ac.mutex_);
81 ac.contexts_.erase(
this);
92 if (
request_.allowed_planning_time <= 0.0)
94 RCLCPP_INFO(getLogger(),
"The timeout for planning must be positive (%lf specified). Assuming one second instead.",
96 request_.allowed_planning_time = 1.0;
98 if (
request_.num_planning_attempts < 0)
100 RCLCPP_ERROR(getLogger(),
"The number of desired planning attempts should be positive. "
101 "Assuming one attempt.");
103 request_.num_planning_attempts = std::max(1,
request_.num_planning_attempts);
107 const rclcpp::Node::SharedPtr& ,
const std::string& )
120 moveit_msgs::msg::MoveItErrorCodes dummy;
137 ActiveContexts& ac = getActiveContexts();
138 std::scoped_lock _(ac.mutex_);
140 context->terminate();
void terminate() const
Request termination, if a solve() function is currently computing plans.
virtual std::string getDescription() const =0
Get a short string that identifies the planning interface.
virtual void getPlanningAlgorithms(std::vector< std::string > &algs) const
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace)
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
Representation of a particular planning context – the planning scene and the request are known,...
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
MotionPlanRequest request_
The planning request for this context.
virtual ~PlanningContext()
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.
std::set< PlanningContext * > contexts_