38 #include <boost/thread/mutex.hpp> 52 static ActiveContexts& getActiveContexts()
54 static ActiveContexts ac;
61 ActiveContexts& ac = getActiveContexts();
62 boost::mutex::scoped_lock _(ac.mutex_);
63 ac.contexts_.insert(
this);
68 ActiveContexts& ac = getActiveContexts();
69 boost::mutex::scoped_lock _(ac.mutex_);
70 ac.contexts_.erase(
this);
81 if (
request_.allowed_planning_time <= 0.0)
84 "The timeout for planning must be positive (%lf specified). Assuming one second instead.",
86 request_.allowed_planning_time = 1.0;
88 if (
request_.num_planning_attempts < 0)
89 ROS_ERROR_NAMED(
"planning_interface",
"The number of desired planning attempts should be positive. " 90 "Assuming one attempt.");
91 request_.num_planning_attempts = std::max(1,
request_.num_planning_attempts);
107 moveit_msgs::MoveItErrorCodes dummy;
108 return getPlanningContext(planning_scene, req, dummy);
119 config_settings_ = pcs;
124 ActiveContexts& ac = getActiveContexts();
125 boost::mutex::scoped_lock _(ac.mutex_);
126 for (std::set<PlanningContext*>::iterator it = ac.contexts_.begin(); it != ac.contexts_.end(); ++it)
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
#define ROS_INFO_NAMED(name,...)
std::set< PlanningContext * > contexts_
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
virtual bool initialize(const robot_model::RobotModelConstPtr &model, const std::string &ns)
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
This namespace includes the central class for representing planning contexts.
moveit_msgs::MotionPlanRequest MotionPlanRequest
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 std::string getDescription() const
Get.
virtual ~PlanningContext()
#define ROS_ERROR_NAMED(name,...)
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
This namespace includes the base class for MoveIt! planners.
void terminate() const
Request termination, if a solve() function is currently computing plans.
MotionPlanRequest request_
The planning request for this context.