37#include <boost/algorithm/string/trim.hpp>
38#include <boost/algorithm/string/split.hpp>
39#include <boost/algorithm/string/replace.hpp>
40#include <boost/lexical_cast.hpp>
55#include <ompl/config.h>
56#include <ompl/base/samplers/UniformValidStateSampler.h>
57#include <ompl/base/goals/GoalLazySamples.h>
58#include <ompl/tools/config/SelfConfig.h>
59#include <ompl/base/spaces/SE3StateSpace.h>
60#include <ompl/datastructures/PDF.h>
61#include <ompl/base/terminationconditions/IterationTerminationCondition.h>
62#include <ompl/base/terminationconditions/CostConvergenceTerminationCondition.h>
64#include <ompl/base/objectives/PathLengthOptimizationObjective.h>
65#include <ompl/base/objectives/MechanicalWorkOptimizationObjective.h>
66#include <ompl/base/objectives/MinimaxObjective.h>
67#include <ompl/base/objectives/StateCostIntegralObjective.h>
68#include <ompl/base/objectives/MaximizeMinClearanceObjective.h>
69#include <ompl/geometric/planners/prm/LazyPRM.h>
83 :
planning_interface::PlanningContext(name, spec.state_space_->getJointModelGroup()->getName())
85 , complete_initial_robot_state_(spec.state_space_->getRobotModel())
86 , ompl_simple_setup_(spec.ompl_simple_setup_)
87 , ompl_benchmark_(*ompl_simple_setup_)
88 , ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition())
90 , last_plan_time_(0.0)
91 , last_simplify_time_(0.0)
92 , max_goal_samples_(0)
93 , max_state_sampling_attempts_(0)
94 , max_goal_sampling_attempts_(0)
95 , max_planning_threads_(0)
96 , max_solution_segment_length_(0.0)
97 , minimum_waypoint_count_(0)
98 , multi_query_planning_enabled_(false)
99 , simplify_solutions_(true)
112 if (!use_constraints_approximations)
127 ompl_simple_setup_->setStateValidityChecker(std::make_shared<ConstrainedPlanningStateValidityChecker>(
this));
135 ompl_simple_setup_->setStateValidityChecker(std::make_shared<StateValidityChecker>(
this));
140 const ConstraintApproximationPtr& constraint_approx =
142 if (constraint_approx)
144 getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
145 RCLCPP_INFO(getLogger(),
"Using precomputed interpolation states");
158 RCLCPP_ERROR(getLogger(),
"No state space is configured yet");
168 if (peval.find_first_of(
"link(") == 0 && peval[peval.length() - 1] ==
')')
170 std::string link_name = peval.substr(5, peval.length() - 6);
173 return std::make_shared<ProjectionEvaluatorLinkPose>(
this, link_name);
177 RCLCPP_ERROR(getLogger(),
178 "Attempted to set projection evaluator with respect to position of link '%s', "
179 "but that link is not known to the kinematic model.",
183 else if (peval.find_first_of(
"joints(") == 0 && peval[peval.length() - 1] ==
')')
185 std::string joints = peval.substr(7, peval.length() - 8);
186 boost::replace_all(joints,
",",
" ");
187 std::vector<unsigned int> j;
188 std::stringstream ss(joints);
189 while (ss.good() && !ss.eof())
192 ss >> joint >> std::ws;
196 if (variable_count > 0)
199 for (
unsigned int q = 0; q < variable_count; ++q)
201 j.push_back(idx + q);
206 RCLCPP_WARN(getLogger(),
"%s: Ignoring joint '%s' in projection since it has 0 DOF",
name_.c_str(),
212 RCLCPP_ERROR(getLogger(),
213 "%s: Attempted to set projection evaluator with respect to value of joint "
214 "'%s', but that joint is not known to the group '%s'.",
220 RCLCPP_ERROR(getLogger(),
"%s: No valid joints specified for joint projection",
name_.c_str());
224 return std::make_shared<ProjectionEvaluatorJointValue>(
this, j);
229 RCLCPP_ERROR(getLogger(),
"Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
231 return ob::ProjectionEvaluatorPtr();
234ompl::base::StateSamplerPtr
239 RCLCPP_ERROR(getLogger(),
"%s: Attempted to allocate a state sampler for an unknown state space",
name_.c_str());
240 return ompl::base::StateSamplerPtr();
243 RCLCPP_DEBUG(getLogger(),
"%s: Allocating a new state sampler (attempts to use path constraints)",
name_.c_str());
249 const ConstraintApproximationPtr& constraint_approx =
251 if (constraint_approx)
253 ompl::base::StateSamplerAllocator state_sampler_allocator =
255 if (state_sampler_allocator)
257 ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
260 RCLCPP_INFO(getLogger(),
261 "%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
263 return state_sampler;
269 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
276 if (constraint_sampler)
278 RCLCPP_INFO(getLogger(),
"%s: Allocating specialized state sampler for state space",
name_.c_str());
279 return std::make_shared<ConstrainedSampler>(
this, constraint_sampler);
282 RCLCPP_DEBUG(getLogger(),
"%s: Allocating default state sampler for state space",
name_.c_str());
283 return state_space->allocDefaultStateSampler();
288 const std::map<std::string, std::string>& config =
spec_.
config_;
291 std::map<std::string, std::string> cfg = config;
294 auto it = cfg.find(
"longest_valid_segment_fraction");
299 double longest_valid_segment_fraction_config = (it != cfg.end())
302 double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
307 longest_valid_segment_fraction_final = std::min(
308 longest_valid_segment_fraction_config,
319 it = cfg.find(
"projection_evaluator");
331 std::string optimizer;
332 ompl::base::OptimizationObjectivePtr objective;
333 it = cfg.find(
"optimization_objective");
336 optimizer = it->second;
339 if (optimizer ==
"PathLengthOptimizationObjective")
342 std::make_shared<ompl::base::PathLengthOptimizationObjective>(
ompl_simple_setup_->getSpaceInformation());
344 else if (optimizer ==
"MinimaxObjective")
346 objective = std::make_shared<ompl::base::MinimaxObjective>(
ompl_simple_setup_->getSpaceInformation());
348 else if (optimizer ==
"StateCostIntegralObjective")
350 objective = std::make_shared<ompl::base::StateCostIntegralObjective>(
ompl_simple_setup_->getSpaceInformation());
352 else if (optimizer ==
"MechanicalWorkOptimizationObjective")
355 std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(
ompl_simple_setup_->getSpaceInformation());
357 else if (optimizer ==
"MaximizeMinClearanceObjective")
360 std::make_shared<ompl::base::MaximizeMinClearanceObjective>(
ompl_simple_setup_->getSpaceInformation());
364 RCLCPP_WARN(getLogger(),
365 "Optimization objective %s is invalid or not defined, using PathLengthOptimizationObjective instead",
368 std::make_shared<ompl::base::PathLengthOptimizationObjective>(
ompl_simple_setup_->getSpaceInformation());
375 it = cfg.find(
"multi_query_planning_enabled");
382 it = cfg.find(
"interpolate");
390 it = cfg.find(
"simplify_solutions");
398 it = cfg.find(
"hybridize");
401 hybridize_ = boost::lexical_cast<bool>(it->second);
406 it = cfg.find(
"type");
410 RCLCPP_WARN(getLogger(),
"%s: Attribute 'type' not specified in planner configuration",
name_.c_str());
414 std::string type = it->second;
419 const ompl::base::SpaceInformationPtr& si) { return allocator(si, planner_name, spec); });
420 RCLCPP_INFO(getLogger(),
421 "Planner configuration '%s' will use planner '%s'. "
422 "Additional configuration parameters will be set when the planner is constructed.",
423 name_.c_str(), type.c_str());
435 if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
436 wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
437 wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
439 RCLCPP_WARN(getLogger(),
"It looks like the planning volume was not specified.");
442 RCLCPP_DEBUG(getLogger(),
443 "%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = "
444 "[%f, %f], z = [%f, %f]",
445 name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
446 wparams.min_corner.z, wparams.max_corner.z);
448 spec_.
state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
449 wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
454 ompl::time::point start = ompl::time::now();
470 unsigned int eventual_states = 1;
471 std::vector<ompl::base::State*> states = pg.getStates();
472 for (
size_t i = 0; i < states.size() - 1; ++i)
474 eventual_states +=
ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
494 for (std::size_t i = 0; i < pg.getStateCount(); ++i)
523 std::vector<ob::GoalPtr> goals;
524 for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint :
goal_constraints_)
526 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
530 goal_constraint->getAllConstraints());
533 if (constraint_sampler)
535 ob::GoalPtr goal = std::make_shared<ConstrainedGoalSampler>(
this, goal_constraint, constraint_sampler);
536 goals.push_back(goal);
542 return goals.size() == 1 ? goals[0] : std::make_shared<GoalSampleableRegionMux>(goals);
546 RCLCPP_ERROR(getLogger(),
"Unable to construct goal representation");
549 return ob::GoalPtr();
552ompl::base::PlannerTerminationCondition
558 return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
561 std::string termination_string = it->second;
562 std::vector<std::string> termination_and_params;
563 boost::split(termination_and_params, termination_string, boost::is_any_of(
"[ ,]"));
565 if (termination_and_params.empty())
567 RCLCPP_ERROR(getLogger(),
"Termination condition not specified");
573 else if (termination_and_params[0] ==
"Iteration")
575 if (termination_and_params.size() > 1)
577 return ob::plannerOrTerminationCondition(
578 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
579 ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
583 RCLCPP_ERROR(getLogger(),
"Missing argument to Iteration termination condition");
588 else if (termination_and_params[0] ==
"CostConvergence")
590 std::size_t solutions_window = 10u;
591 double epsilon = 0.1;
592 if (termination_and_params.size() > 1)
594 solutions_window = std::stoul(termination_and_params[1]);
595 if (termination_and_params.size() > 2)
600 return ob::plannerOrTerminationCondition(
601 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
602 ob::CostConvergenceTerminationCondition(
ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon));
607 else if (termination_and_params[0] ==
"ExactSolution")
609 return ob::plannerOrTerminationCondition(
610 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
611 ob::exactSolnPlannerTerminationCondition(
ompl_simple_setup_->getProblemDefinition()));
615 RCLCPP_ERROR(getLogger(),
"Unknown planner termination condition");
618 return ob::plannerAlwaysTerminatingCondition();
639 auto planner =
dynamic_cast<ompl::geometric::LazyPRM*
>(
ompl_simple_setup_->getPlanner().get());
640 if (planner !=
nullptr)
642 planner->clearValidity();
654 moveit_msgs::msg::MoveItErrorCodes* )
665 const moveit_msgs::msg::Constraints& path_constraints,
666 moveit_msgs::msg::MoveItErrorCodes* error)
670 for (
const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
673 kinematic_constraints::KinematicConstraintSetPtr kset(
684 RCLCPP_WARN(getLogger(),
"%s: No goal constraints specified. There is no problem to solve.",
name_.c_str());
687 error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
694 return static_cast<bool>(goal);
705 ot::Benchmark::Request req;
706 req.maxTime = timeout;
707 req.runCount = count;
708 req.displayProgress =
true;
709 req.saveConsoleOutput =
false;
752 ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
758 int v =
ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
759 int iv =
ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
760 RCLCPP_DEBUG(getLogger(),
"There were %d valid motions and %d invalid motions.", v, iv);
763 RCLCPP_DEBUG(getLogger(),
"%s",
765 std::stringstream debug_out;
767 return debug_out.str();
776 if (res.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
778 RCLCPP_ERROR(getLogger(),
"Unable to solve the planning problem");
794 RCLCPP_DEBUG(getLogger(),
"%s: Returning successful solution with %lu states",
getName().c_str(),
806 if (res.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
808 RCLCPP_INFO(getLogger(),
"Unable to solve the planning problem");
835 ompl::time::point start_interpolate = ompl::time::now();
837 res.
processing_time.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
844 RCLCPP_DEBUG(getLogger(),
"%s: Returning successful solution with %lu states",
getName().c_str(),
850 ompl::time::point start = ompl::time::now();
853 moveit_msgs::msg::MoveItErrorCodes result;
854 result.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
857 RCLCPP_DEBUG(getLogger(),
"%s: Solving the planning problem once...",
name_.c_str());
868 RCLCPP_DEBUG(getLogger(),
"%s: Solving the planning problem %u times...",
name_.c_str(), count);
875 for (
unsigned int i = 0; i < count; ++i)
882 for (
unsigned int i = 0; i < count; ++i)
892 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
902 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
903 for (
int i = 0; i < n && !ptc(); ++i)
923 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
924 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
925 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
933 for (
int i = 0; i < n; ++i)
940 for (
int i = 0; i < n; ++i)
948 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
949 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
950 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
963 std::unique_lock<std::mutex> slock(
ptc_lock_);
969 std::unique_lock<std::mutex> slock(
ptc_lock_);
975 auto result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
976 const ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
977 switch (ompl::base::PlannerStatus::StatusType(ompl_status))
979 case ompl::base::PlannerStatus::UNKNOWN:
980 RCLCPP_WARN(getLogger(),
"Motion planning failed for an unknown reason");
981 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
983 case ompl::base::PlannerStatus::INVALID_START:
984 RCLCPP_WARN(getLogger(),
"Invalid start state");
985 result = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
987 case ompl::base::PlannerStatus::INVALID_GOAL:
988 RCLCPP_WARN(getLogger(),
"Invalid goal state");
989 result = moveit_msgs::msg::MoveItErrorCodes::GOAL_STATE_INVALID;
991 case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
992 RCLCPP_WARN(getLogger(),
"Unrecognized goal type");
993 result = moveit_msgs::msg::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
995 case ompl::base::PlannerStatus::TIMEOUT:
996 RCLCPP_WARN(getLogger(),
"Timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
998 result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
1000 case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
1002 if (ompl_simple_setup->getLastPlanComputationTime() >
request_.allowed_planning_time)
1004 RCLCPP_WARN(getLogger(),
"Planning timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
1006 result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
1010 RCLCPP_WARN(getLogger(),
"Solution is approximate");
1011 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1014 case ompl::base::PlannerStatus::EXACT_SOLUTION:
1015 result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1017 case ompl::base::PlannerStatus::CRASH:
1018 RCLCPP_WARN(getLogger(),
"OMPL crashed!");
1019 result = moveit_msgs::msg::MoveItErrorCodes::CRASH;
1021 case ompl::base::PlannerStatus::ABORT:
1022 RCLCPP_WARN(getLogger(),
"OMPL was aborted");
1023 result = moveit_msgs::msg::MoveItErrorCodes::ABORT;
1027 RCLCPP_WARN(getLogger(),
"Unexpected PlannerStatus code from OMPL.");
1028 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1035 std::unique_lock<std::mutex> slock(
ptc_lock_);
1045 std::string constraint_path;
1046 if (node->get_parameter(
"constraint_approximations_path", constraint_path))
1051 RCLCPP_WARN(getLogger(),
"ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
1057 std::string constraint_path;
1058 if (node->get_parameter(
"constraint_approximations_path", constraint_path))
1061 std::stringstream ss;
1063 RCLCPP_INFO_STREAM(getLogger(), ss.str());
A class that contains many different constraints, and can check RobotState *versus the full set....
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
int32_t logPlannerStatus(const og::SimpleSetupPtr &ompl_simple_setup)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
void setVerboseStateValidityChecks(bool flag)
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
unsigned int minimum_waypoint_count_
void clear() override
Clear the data structures used by the planner.
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
double last_plan_time_
the time spent computing the last plan
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
const ob::PlannerTerminationCondition * ptc_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
bool loadConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
std::vector< int > space_signature_
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
void interpolateSolution()
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
bool saveConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
const moveit::core::RobotState & getCompleteInitialRobotState() const
double getLastPlanTime() const
bool multi_query_planning_enabled_
when false, clears planners before running solve()
virtual void configure(const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations)
Configure ompl_simple_setup_ and optionally the constraints_library_.
bool setGoalConstraints(const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
const moveit::core::RobotModelConstPtr & getRobotModel() const
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used
moveit::core::RobotState complete_initial_robot_state_
void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters &wparams)
const moveit::core::JointModelGroup * getJointModelGroup() const
double getLastSimplifyTime() const
moveit_msgs::msg::Constraints path_constraints_msg_
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
ConstraintsLibraryPtr constraints_library_
void unregisterTerminationCondition()
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
bool terminate() override
If solve() is running, terminate the computation. Return false if termination not possible....
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
void simplifySolution(double timeout)
void setProjectionEvaluator(const std::string &peval)
void solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
ModelBasedPlanningContextSpecification spec_
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
virtual ob::GoalPtr constructGoal()
double last_simplify_time_
the time spent simplifying the last plan
double max_solution_segment_length_
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
An interface for a OMPL state validity checker.
std::string name_
The name of this planning context.
MotionPlanRequest request_
The planning request for this context.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
const std::string & getName() const
Get the name of this planning context.
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
RobotTrajectory & clear()
locale-agnostic conversion functions from floating point numbers to strings
rclcpp::Logger getLogger()
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
double toDouble(const std::string &s)
Converts a std::string to double using the classic C locale.
std::string toString(double d)
Convert a double to std::string using the classic C locale.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
The MoveIt interface to OMPL.
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
This namespace includes the base class for MoveIt planners.
ModelBasedStateSpacePtr state_space_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
std::map< std::string, std::string > config_
ConfiguredPlannerSelector planner_selector_
moveit_msgs::msg::MoveItErrorCodes error_code
std::vector< std::string > description
std::vector< double > processing_time
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory