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);
66 PlanningContext::~PlanningContext()
68 ActiveContexts& ac = getActiveContexts();
69 boost::mutex::scoped_lock _(ac.mutex_);
70 ac.contexts_.erase(
this);
73 void PlanningContext::setPlanningScene(
const planning_scene::PlanningSceneConstPtr&
planning_scene)
81 if (request_.allowed_planning_time <= 0.0)
84 "The timeout for planning must be positive (%lf specified). Assuming one second instead.",
85 request_.allowed_planning_time);
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);
94 bool PlannerManager::initialize(
const moveit::core::RobotModelConstPtr& ,
const std::string& )
99 std::string PlannerManager::getDescription()
const
104 PlanningContextPtr PlannerManager::getPlanningContext(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
107 moveit_msgs::MoveItErrorCodes dummy;
111 void PlannerManager::getPlanningAlgorithms(std::vector<std::string>& algs)
const
119 config_settings_ = pcs;
122 void PlannerManager::terminate()
const
124 ActiveContexts& ac = getActiveContexts();
125 boost::mutex::scoped_lock _(ac.mutex_);