37 #include <boost/algorithm/string/trim.hpp>    51 #include <ompl/base/samplers/UniformValidStateSampler.h>    52 #include <ompl/base/goals/GoalLazySamples.h>    53 #include <ompl/tools/config/SelfConfig.h>    54 #include <ompl/base/spaces/SE3StateSpace.h>    55 #include <ompl/datastructures/PDF.h>    57 #include "ompl/base/objectives/PathLengthOptimizationObjective.h"    58 #include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"    59 #include "ompl/base/objectives/MinimaxObjective.h"    60 #include "ompl/base/objectives/StateCostIntegralObjective.h"    61 #include "ompl/base/objectives/MaximizeMinClearanceObjective.h"    67   , complete_initial_robot_state_(spec.state_space_->getRobotModel())
    68   , ompl_simple_setup_(spec.ompl_simple_setup_)
    69   , ompl_benchmark_(*ompl_simple_setup_)
    70   , ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition())
    72   , last_plan_time_(0.0)
    73   , last_simplify_time_(0.0)
    74   , max_goal_samples_(0)
    75   , max_state_sampling_attempts_(0)
    76   , max_goal_sampling_attempts_(0)
    77   , max_planning_threads_(0)
    78   , max_solution_segment_length_(0.0)
    79   , minimum_waypoint_count_(0)
    80   , use_state_validity_cache_(true)
    81   , simplify_solutions_(true)
    93     ROS_ERROR_NAMED(
"model_based_planning_context", 
"No state space is configured yet");
   101 ompl::base::ProjectionEvaluatorPtr
   104   if (peval.find_first_of(
"link(") == 0 && peval[peval.length() - 1] == 
')')
   106     std::string link_name = peval.substr(5, peval.length() - 6);
   111                       "Attempted to set projection evaluator with respect to position of link '%s', "   112                       "but that link is not known to the kinematic model.",
   115   else if (peval.find_first_of(
"joints(") == 0 && peval[peval.length() - 1] == 
')')
   117     std::string joints = peval.substr(7, peval.length() - 8);
   118     boost::replace_all(joints, 
",", 
" ");
   119     std::vector<unsigned int> j;
   120     std::stringstream ss(joints);
   121     while (ss.good() && !ss.eof())
   131           for (
unsigned int q = 0; q < vc; ++q)
   132             j.push_back(idx + q);
   135           ROS_WARN_NAMED(
"model_based_planning_context", 
"%s: Ignoring joint '%s' in projection since it has 0 DOF",
   136                          name_.c_str(), v.c_str());
   140                         "%s: Attempted to set projection evaluator with respect to value of joint "   141                         "'%s', but that joint is not known to the group '%s'.",
   145       ROS_ERROR_NAMED(
"model_based_planning_context", 
"%s: No valid joints specified for joint projection",
   152                     "Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
   153   return ob::ProjectionEvaluatorPtr();
   156 ompl::base::StateSamplerPtr
   162                     "%s: Attempted to allocate a state sampler for an unknown state space", 
name_.c_str());
   163     return ompl::base::StateSamplerPtr();
   167                   "%s: Allocating a new state sampler (attempts to use path constraints)", 
name_.c_str());
   173       const ConstraintApproximationPtr& ca =
   180           ompl::base::StateSamplerPtr res = c_ssa(ss);
   184                            "%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
   192     constraint_samplers::ConstraintSamplerPtr cs;
   199       ROS_INFO_NAMED(
"model_based_planning_context", 
"%s: Allocating specialized state sampler for state space",
   204   ROS_DEBUG_NAMED(
"model_based_planning_context", 
"%s: Allocating default state sampler for state space",
   206   return ss->allocDefaultStateSampler();
   219     const ConstraintApproximationPtr& ca =
   224       ROS_INFO_NAMED(
"model_based_planning_context", 
"Using precomputed interpolation states");
   235   const std::map<std::string, std::string>& config = 
spec_.
config_;
   238   std::map<std::string, std::string> cfg = config;
   241   std::map<std::string, std::string>::iterator it = cfg.find(
"longest_valid_segment_fraction");
   246     double longest_valid_segment_fraction_config = (it != cfg.end())
   249     double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
   254       longest_valid_segment_fraction_final = std::min(
   255           longest_valid_segment_fraction_config,
   266   it = cfg.find(
"projection_evaluator");
   276   std::string optimizer;
   277   ompl::base::OptimizationObjectivePtr objective;
   278   it = cfg.find(
"optimization_objective");
   281     optimizer = 
"PathLengthOptimizationObjective";
   282     ROS_DEBUG_NAMED(
"model_based_planning_context", 
"No optimization objective specified, defaulting to %s",
   287     optimizer = it->second;
   291   if (optimizer == 
"PathLengthOptimizationObjective")
   293     objective.reset(
new ompl::base::PathLengthOptimizationObjective(
ompl_simple_setup_->getSpaceInformation()));
   295   else if (optimizer == 
"MinimaxObjective")
   297     objective.reset(
new ompl::base::MinimaxObjective(
ompl_simple_setup_->getSpaceInformation()));
   299   else if (optimizer == 
"StateCostIntegralObjective")
   301     objective.reset(
new ompl::base::StateCostIntegralObjective(
ompl_simple_setup_->getSpaceInformation()));
   303   else if (optimizer == 
"MechanicalWorkOptimizationObjective")
   305     objective.reset(
new ompl::base::MechanicalWorkOptimizationObjective(
ompl_simple_setup_->getSpaceInformation()));
   307   else if (optimizer == 
"MaximizeMinClearanceObjective")
   309     objective.reset(
new ompl::base::MaximizeMinClearanceObjective(
ompl_simple_setup_->getSpaceInformation()));
   313     objective.reset(
new ompl::base::PathLengthOptimizationObjective(
ompl_simple_setup_->getSpaceInformation()));
   319   it = cfg.find(
"type");
   323       ROS_WARN_NAMED(
"model_based_planning_context", 
"%s: Attribute 'type' not specified in planner configuration",
   328     std::string type = it->second;
   333                    "Planner configuration '%s' will use planner '%s'. "   334                    "Additional configuration parameters will be set when the planner is constructed.",
   335                    name_.c_str(), type.c_str());
   347   if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
   348       wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
   349       wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
   350     ROS_WARN_NAMED(
"model_based_planning_context", 
"It looks like the planning volume was not specified.");
   353                   "%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = "   354                   "[%f, %f], z = [%f, %f]",
   355                   name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
   356                   wparams.min_corner.z, wparams.max_corner.z);
   358   spec_.
state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
   359                                         wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
   376     unsigned int eventual_states = 1;
   377     std::vector<ompl::base::State*> states = pg.getStates();
   378     for (
size_t i = 0; i < states.size() - 1; i++)
   380       eventual_states += 
ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
   400   for (std::size_t i = 0; i < pg.getStateCount(); ++i)
   419     static_cast<StateValidityChecker*>(
ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
   426   std::vector<ob::GoalPtr> goals;
   429     constraint_samplers::ConstraintSamplerPtr cs;
   443     ROS_ERROR_NAMED(
"model_based_planning_context", 
"Unable to construct goal representation");
   445   return ob::GoalPtr();
   449     const robot_state::RobotState& complete_initial_robot_state)
   467                                                                    moveit_msgs::MoveItErrorCodes* error)
   478     const std::vector<moveit_msgs::Constraints>& goal_constraints, 
const moveit_msgs::Constraints& path_constraints,
   479     moveit_msgs::MoveItErrorCodes* error)
   483   for (std::size_t i = 0; i < goal_constraints.size(); ++i)
   486     kinematic_constraints::KinematicConstraintSetPtr kset(
   495     ROS_WARN_NAMED(
"model_based_planning_context", 
"%s: No goal constraints specified. There is no problem to solve.",
   498       error->val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
   511                                                           const std::string& filename)
   519   ot::Benchmark::Request req;
   520   req.maxTime = timeout;
   521   req.runCount = count;
   522   req.displayProgress = 
true;
   523   req.saveConsoleOutput = 
false;
   556   ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
   562   int v = 
ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
   563   int iv = 
ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
   564   ROS_DEBUG_NAMED(
"model_based_planning_context", 
"There were %d valid motions and %d invalid motions.", v, iv);
   567     ROS_WARN_NAMED(
"model_based_planning_context", 
"Computed solution is approximate");
   583     ROS_DEBUG_NAMED(
"model_based_planning_context", 
"%s: Returning successful solution with %lu states",
   593     ROS_INFO_NAMED(
"model_based_planning_context", 
"Unable to solve the planning problem");
   594     res.
error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
   624     ompl::time::point start_interpolate = ompl::time::now();
   626     res.
processing_time_.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
   633     ROS_DEBUG_NAMED(
"model_based_planning_context", 
"%s: Returning successful solution with %lu states",
   639     ROS_INFO_NAMED(
"model_based_planning_context", 
"Unable to solve the planning problem");
   640     res.
error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
   648   ompl::time::point start = ompl::time::now();
   654     ROS_DEBUG_NAMED(
"model_based_planning_context", 
"%s: Solving the planning problem once...", 
name_.c_str());
   655     ob::PlannerTerminationCondition ptc =
   656         ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
   664     ROS_DEBUG_NAMED(
"model_based_planning_context", 
"%s: Solving the planning problem %u times...", 
name_.c_str(),
   671         for (
unsigned int i = 0; i < count; ++i)
   674         for (
unsigned int i = 0; i < count; ++i)
   677       ob::PlannerTerminationCondition ptc =
   678           ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
   680       result = 
ompl_parallel_plan_.solve(ptc, 1, count, 
true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
   686       ob::PlannerTerminationCondition ptc =
   687           ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
   691       for (
int i = 0; i < n && ptc() == 
false; ++i)
   700         bool r = 
ompl_parallel_plan_.solve(ptc, 1, count, 
true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
   701         result = result && r;
   704       if (n && ptc() == 
false)
   708           for (
int i = 0; i < n; ++i)
   711           for (
int i = 0; i < n; ++i)
   713         bool r = 
ompl_parallel_plan_.solve(ptc, 1, count, 
true) == ompl::base::PlannerStatus::EXACT_SOLUTION;
   714         result = result && r;
   728   boost::mutex::scoped_lock slock(
ptc_lock_);
   734   boost::mutex::scoped_lock slock(
ptc_lock_);
   740   boost::mutex::scoped_lock slock(
ptc_lock_);
 
double last_simplify_time_
the time spent simplifying the last plan 
robot_trajectory::RobotTrajectoryPtr trajectory_
ModelBasedStateSpacePtr state_space_
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners 
#define ROS_INFO_NAMED(name,...)
void setProjectionEvaluator(const std::string &peval)
#define ROS_WARN_NAMED(name,...)
std::vector< std::string > description_
double toDouble(const std::string &s)
double getLastSimplifyTime() const 
std::string getName(void *handle)
const og::SimpleSetupPtr & getOMPLSimpleSetup() const 
const robot_model::JointModelGroup * getJointModelGroup() const 
void setPlanningVolume(const moveit_msgs::WorkspaceParameters &wparams)
const robot_state::RobotState & getCompleteInitialRobotState() const 
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const 
void simplifySolution(double timeout)
moveit_msgs::MoveItErrorCodes error_code_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time ...
#define ROS_DEBUG_NAMED(name,...)
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
double last_plan_time_
the time spent computing the last plan 
const ob::PlannerTerminationCondition * ptc_
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
moveit_msgs::MoveItErrorCodes error_code_
double max_solution_segment_length_
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const 
ConfiguredPlannerSelector planner_selector_
void unregisterTerminationCondition()
std::vector< double > processing_time_
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const 
void setVerboseStateValidityChecks(bool flag)
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used ...
ModelBasedPlanningContextSpecification spec_
std::vector< int > space_signature_
const std::string & getGroupName() const 
std::string toString(double d)
bool setGoalConstraints(const std::vector< moveit_msgs::Constraints > &goal_constraints, const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
unsigned int minimum_waypoint_count_
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
double getLastPlanTime() const 
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const 
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
const std::string & getName() const 
bool setPathConstraints(const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
#define ROS_ERROR_NAMED(name,...)
moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints &first, const moveit_msgs::Constraints &second)
An interface for a OMPL state validity checker. 
virtual ob::GoalPtr constructGoal()
MotionPlanRequest request_
void interpolateSolution()
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const 
std::map< std::string, std::string > config_
void addSuffixWayPoint(const robot_state::RobotState &state, double dt)
const robot_model::RobotModelConstPtr & getRobotModel() const 
ConstraintsLibraryConstPtr constraints_library_
virtual bool solve(planning_interface::MotionPlanResponse &res)
boost::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
robot_state::RobotState complete_initial_robot_state_
void setCompleteInitialState(const robot_state::RobotState &complete_initial_robot_state)
moveit_msgs::Constraints path_constraints_msg_
const ModelBasedStateSpacePtr & getOMPLStateSpace() const