moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
generate_state_database.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage, Inc.
5 * Copyright (c) 2018, Michael 'v4hn' Goerner
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35
36/* Authors: Ioan Sucan, Michael Goerner */
37
41
44
47
48#include <boost/math/constants/constants.hpp>
49#include <sstream>
50
51static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.planners_ompl.generate_state_database");
52
53static const std::string ROBOT_DESCRIPTION = "robot_description";
54
55static const std::string CONSTRAINT_PARAMETER = "constraints";
56
57static bool getUintParameterOr(const rclcpp::Node::SharedPtr& node, const std::string& param_name,
58 size_t&& result_value, const size_t default_value)
59{
60 int param_value;
61 if (node->get_parameter(param_name, param_value))
62 {
63 if (param_value >= 0)
64 {
65 result_value = static_cast<size_t>(param_value);
66 return true;
67 }
68
69 RCLCPP_WARN_STREAM(LOGGER, "Value for parameter '" << param_name
70 << "' must be positive\n"
71 "Using back to default value:"
72 << default_value);
73 }
74
75 result_value = default_value;
76 return true;
77}
78
80{
81 bool setFromNode(const rclcpp::Node::SharedPtr& node)
82 {
83 node->get_parameter_or("use_current_scene", use_current_scene, false);
84
85 // number of states in joint space approximation
86 getUintParameterOr(node, "state_cnt", construction_opts.samples, 10000);
87
88 // generate edges together with states?
89 getUintParameterOr(node, "edges_per_sample", construction_opts.edges_per_sample, 0);
90
91 node->get_parameter_or("max_edge_length", construction_opts.max_edge_length, 0.2);
92
93 // verify constraint validity on edges
94 node->get_parameter_or("explicit_motions", construction_opts.explicit_motions, true);
95 node->get_parameter_or("explicit_points_resolution", construction_opts.explicit_points_resolution, 0.05);
96 getUintParameterOr(node, "max_explicit_points", construction_opts.max_explicit_points, 200);
97
98 // local planning in JointModel state space
99 node->get_parameter_or("state_space_parameterization", construction_opts.state_space_parameterization,
100 std::string("JointModel"));
101
102 node->get_parameter_or("output_folder", output_folder, std::string("constraint_approximation_database"));
103
104 if (!node->get_parameter("planning_group", planning_group))
105 {
106 RCLCPP_FATAL(LOGGER, "~planning_group parameter has to be specified.");
107 return false;
108 }
109
110 if (!kinematic_constraints::constructConstraints(node, CONSTRAINT_PARAMETER, constraints))
111 {
112 RCLCPP_FATAL_STREAM(LOGGER,
113 "Could not find valid constraint description in parameter '"
114 << node->get_fully_qualified_name() << '.' << CONSTRAINT_PARAMETER
115 << "'. "
116 "Please upload correct correct constraint description or remap the parameter.");
117 return false;
118 }
119
120 return true;
121 };
122
123 std::string planning_group;
124
125 // path to folder for generated database
126 std::string output_folder;
127
128 // request the current scene via get_planning_scene service
130
131 // constraints the approximation should satisfy
132 moveit_msgs::msg::Constraints constraints;
133
134 // internal parameters of approximation generator
136};
137
138void computeDB(const rclcpp::Node::SharedPtr& node, const planning_scene::PlanningScenePtr& scene,
139 struct GenerateStateDatabaseParameters& params)
140{
141 // required by addConstraintApproximation
142 scene->getCurrentStateNonConst().update();
143
144 ompl_interface::OMPLInterface ompl_interface(scene->getRobotModel(), node, "ompl");
146 req.group_name = params.planning_group;
147 req.path_constraints = params.constraints;
148 moveit::core::robotStateToRobotStateMsg(scene->getCurrentState(), req.start_state);
149 req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
150 scene->getCurrentState(), scene->getRobotModel()->getJointModelGroup(params.planning_group)));
151
152 ompl_interface::ModelBasedPlanningContextPtr context = ompl_interface.getPlanningContext(scene, req);
153
154 RCLCPP_INFO_STREAM(LOGGER, "Generating Joint Space Constraint Approximation Database for constraint:\n"
155 << params.constraints.name);
156
158 context->getConstraintsLibraryNonConst()->addConstraintApproximation(params.constraints, params.planning_group,
159 scene, params.construction_opts);
160
161 if (!result.approx)
162 {
163 RCLCPP_FATAL(LOGGER, "Failed to generate approximation.");
164 return;
165 }
166 context->getConstraintsLibraryNonConst()->saveConstraintApproximations(params.output_folder);
167 RCLCPP_INFO_STREAM(LOGGER, "Successfully generated Joint Space Constraint Approximation Database for constraint:\n"
168 << params.constraints.name);
169 RCLCPP_INFO_STREAM(LOGGER, "The database has been saved in your local folder '" << params.output_folder << '\'');
170}
171
198int main(int argc, char** argv)
199{
200 rclcpp::init(argc, argv);
201 rclcpp::NodeOptions opt;
202 opt.automatically_declare_parameters_from_overrides(true);
203 std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("generate_state_database", opt);
204
206 if (!params.setFromNode(node))
207 return 1;
208
209 planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION);
210 if (!psm.getRobotModel())
211 return 1;
212
213 if (params.use_current_scene)
214 {
215 RCLCPP_INFO(LOGGER, "Requesting current planning scene to generate database");
216 if (!psm.requestPlanningSceneState())
217 {
218 RCLCPP_FATAL(LOGGER, "Abort. The current scene could not be retrieved.");
219 return 1;
220 }
221 }
222
224 {
225 RCLCPP_FATAL(LOGGER, "Abort. Constraint description is an empty set of constraints.");
226 return 1;
227 }
228
229 computeDB(node, psm.getPlanningScene(), params);
230
231 rclcpp::shutdown();
232
233 return 0;
234}
PlanningSceneMonitor Subscribes to the topic planning_scene.
const moveit::core::RobotModelConstPtr & getRobotModel() const
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
int main(int argc, char **argv)
void computeDB(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene, struct GenerateStateDatabaseParameters &params)
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition utils.cpp:152
bool constructConstraints(const rclcpp::Node::SharedPtr &node, const std::string &constraints_param, moveit_msgs::msg::Constraints &constraints)
extract constraint message from node parameters.
Definition utils.cpp:606
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
The MoveIt interface to OMPL.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
ompl_interface::ConstraintApproximationConstructionOptions construction_opts
bool setFromNode(const rclcpp::Node::SharedPtr &node)
moveit_msgs::msg::Constraints constraints