moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
constrained_planning_state_space_factory.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2020, KU Leuven
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of KU Leuven nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Jeroen De Maeyer */
36/* Mostly copied from Ioan Sucan's code */
37
40
41namespace ompl_interface
42{
47
49 const std::string& /*group*/, const moveit_msgs::msg::MotionPlanRequest& req,
50 const moveit::core::RobotModelConstPtr& /*robot_model*/) const
51{
52 // If we have exactly one position or orientation constraint, prefer the constrained planning state space
53 auto num_constraints =
54 req.path_constraints.position_constraints.size() + req.path_constraints.orientation_constraints.size();
55 if (num_constraints == 1 && req.path_constraints.joint_constraints.empty() &&
56 req.path_constraints.visibility_constraints.empty())
57 {
58 return 200;
59 }
60 // Otherwise, return the lowest priority currently existing in the ompl interface.
61 // This state space will only be selected if it is the only option to choose from.
62 // See header file for more info.
63 return -2;
64}
65
67 const ModelBasedStateSpaceSpecification& space_spec) const
68{
69 return std::make_shared<ConstrainedPlanningStateSpace>(space_spec);
70}
71} // namespace ompl_interface
ModelBasedStateSpacePtr allocStateSpace(const ModelBasedStateSpaceSpecification &space_spec) const override
int canRepresentProblem(const std::string &group, const moveit_msgs::msg::MotionPlanRequest &req, const moveit::core::RobotModelConstPtr &robot_model) const override
Return a priority that this planner should be used for this specific planning problem.
The MoveIt interface to OMPL.