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 
42 
45 
48 
49 #include <boost/math/constants/constants.hpp>
50 #include <sstream>
51 
52 constexpr char LOGNAME[] = "generate_state_database";
53 
54 static const std::string ROBOT_DESCRIPTION = "robot_description";
55 
56 static const std::string CONSTRAINT_PARAMETER = "constraints";
57 
59 {
61  {
62  use_current_scene = nh.param("use_current_scene", false);
63 
64  // number of states in joint space approximation
65  construction_opts.samples = nh.param("state_cnt", 10000);
66 
67  // generate edges together with states?
68  construction_opts.edges_per_sample = nh.param("edges_per_sample", 0);
69  construction_opts.max_edge_length = nh.param("max_edge_length", 0.2);
70 
71  // verify constraint validity on edges
72  construction_opts.explicit_motions = nh.param("explicit_motions", true);
73  construction_opts.explicit_points_resolution = nh.param("explicit_points_resolution", 0.05);
74  construction_opts.max_explicit_points = nh.param("max_explicit_points", 200);
75 
76  // local planning in JointModel state space
78  nh.param<std::string>("state_space_parameterization", "JointModel");
79 
80  output_folder = nh.param<std::string>("output_folder", "constraint_approximations_database");
81 
82  if (!nh.getParam("planning_group", planning_group))
83  {
84  ROS_FATAL_NAMED(LOGNAME, "~planning_group parameter has to be specified.");
85  return false;
86  }
87 
88  XmlRpc::XmlRpcValue constraint_description;
89  if (!nh.getParam(CONSTRAINT_PARAMETER, constraint_description) ||
91  {
93  "Could not find valid constraint description in parameter '"
95  << "'. "
96  "Please upload correct correct constraint description or remap the parameter.");
97  return false;
98  }
99 
100  return true;
101  };
102 
103  std::string planning_group;
104 
105  // path to folder for generated database
106  std::string output_folder;
107 
108  // request the current scene via get_planning_scene service
110 
111  // constraints the approximation should satisfy
112  moveit_msgs::Constraints constraints;
113 
114  // internal parameters of approximation generator
116 };
117 
118 void computeDB(const planning_scene::PlanningScenePtr& scene, struct GenerateStateDatabaseParameters& params)
119 {
120  // required by addConstraintApproximation
121  scene->getCurrentStateNonConst().update();
122 
123  ompl_interface::OMPLInterface ompl_interface(scene->getRobotModel());
125  req.group_name = params.planning_group;
126  req.path_constraints = params.constraints;
127  moveit::core::robotStateToRobotStateMsg(scene->getCurrentState(), req.start_state);
128  req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
129  scene->getCurrentState(), scene->getRobotModel()->getJointModelGroup(params.planning_group)));
130 
131  ompl_interface::ModelBasedPlanningContextPtr context = ompl_interface.getPlanningContext(scene, req);
132 
133  ROS_INFO_STREAM_NAMED(LOGNAME, "Generating Joint Space Constraint Approximation Database for constraint:\n"
134  << params.constraints);
135 
137  context->getConstraintsLibraryNonConst()->addConstraintApproximation(params.constraints, params.planning_group,
138  scene, params.construction_opts);
139 
140  if (!result.approx)
141  {
142  ROS_FATAL_NAMED(LOGNAME, "Failed to generate approximation.");
143  return;
144  }
145  context->getConstraintsLibraryNonConst()->saveConstraintApproximations(params.output_folder);
147  "Successfully generated Joint Space Constraint Approximation Database for constraint:\n"
148  << params.constraints);
149  ROS_INFO_STREAM_NAMED(LOGNAME, "The database has been saved in your local folder '" << params.output_folder << "'");
150 }
151 
165 int main(int argc, char** argv)
166 {
167  ros::init(argc, argv, "construct_tool_constraint_database", ros::init_options::AnonymousName);
168 
170  spinner.start();
171 
172  ros::NodeHandle nh("~");
173 
175  if (!params.setFromHandle(nh))
176  return 1;
177 
179  if (!psm.getRobotModel())
180  return 1;
181 
182  if (params.use_current_scene)
183  {
184  ROS_INFO_NAMED(LOGNAME, "Requesting current planning scene to generate database");
185  if (!psm.requestPlanningSceneState())
186  {
187  ROS_FATAL_NAMED(LOGNAME, "Abort. The current scene could not be retrieved.");
188  return 1;
189  }
190  }
191 
193  {
194  ROS_FATAL_NAMED(LOGNAME, "Abort. Constraint description is an empty set of constraints.");
195  return 1;
196  }
197 
198  computeDB(psm.getPlanningScene(), params);
199 
200  return 0;
201 }
ros::init_options::AnonymousName
AnonymousName
ompl_interface::ConstraintApproximationConstructionOptions::max_explicit_points
unsigned int max_explicit_points
Definition: constraints_library.h:178
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: generate_state_database.cpp:54
ompl_interface::ConstraintApproximationConstructionOptions::samples
unsigned int samples
Definition: constraints_library.h:173
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
GenerateStateDatabaseParameters::setFromHandle
bool setFromHandle(ros::NodeHandle &nh)
Definition: generate_state_database.cpp:60
main
int main(int argc, char **argv)
Definition: generate_state_database.cpp:165
computeDB
void computeDB(const planning_scene::PlanningScenePtr &scene, struct GenerateStateDatabaseParameters &params)
Definition: generate_state_database.cpp:118
utils.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
GenerateStateDatabaseParameters
Definition: generate_state_database.cpp:58
kinematic_constraints::constructConstraints
bool constructConstraints(XmlRpc::XmlRpcValue &params, moveit_msgs::Constraints &constraints)
ros::AsyncSpinner
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
kinematic_constraints::constructGoalConstraints
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
ompl_interface::ConstraintApproximationConstructionResults::approx
ConstraintApproximationPtr approx
Definition: constraints_library.h:183
robot_model_loader.h
ompl_interface.h
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
planning_scene_monitor::PlanningSceneMonitor
ompl_interface::ConstraintApproximationConstructionResults
Definition: constraints_library.h:181
ompl_interface::OMPLInterface
Definition: ompl_interface.h:85
spinner
void spinner()
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
message_checks.h
moveit::core::isEmpty
bool isEmpty(const geometry_msgs::Pose &msg)
planning_scene_monitor::PlanningSceneMonitor::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
GenerateStateDatabaseParameters::planning_group
std::string planning_group
Definition: generate_state_database.cpp:101
ompl_interface::ConstraintApproximationConstructionOptions
Definition: constraints_library.h:160
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
GenerateStateDatabaseParameters::constraints
moveit_msgs::Constraints constraints
Definition: generate_state_database.cpp:112
planning_scene_monitor.h
constraints_library.h
GenerateStateDatabaseParameters::use_current_scene
bool use_current_scene
Definition: generate_state_database.cpp:109
ompl_interface::ConstraintApproximationConstructionOptions::edges_per_sample
unsigned int edges_per_sample
Definition: constraints_library.h:174
ompl_interface::ConstraintApproximationConstructionOptions::explicit_points_resolution
double explicit_points_resolution
Definition: constraints_library.h:177
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
LOGNAME
constexpr char LOGNAME[]
Definition: generate_state_database.cpp:52
GenerateStateDatabaseParameters::output_folder
std::string output_folder
Definition: generate_state_database.cpp:106
GenerateStateDatabaseParameters::construction_opts
ompl_interface::ConstraintApproximationConstructionOptions construction_opts
Definition: generate_state_database.cpp:115
ompl_interface::ConstraintApproximationConstructionOptions::state_space_parameterization
std::string state_space_parameterization
Definition: constraints_library.h:172
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ompl_interface::ConstraintApproximationConstructionOptions::explicit_motions
bool explicit_motions
Definition: constraints_library.h:176
conversions.h
profiler.h
CONSTRAINT_PARAMETER
static const std::string CONSTRAINT_PARAMETER
Definition: generate_state_database.cpp:56
planning_scene_monitor::PlanningSceneMonitor::requestPlanningSceneState
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
ompl_interface::ConstraintApproximationConstructionOptions::max_edge_length
double max_edge_length
Definition: constraints_library.h:175
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
XmlRpc::XmlRpcValue
ros::NodeHandle


ompl
Author(s): Ioan Sucan
autogenerated on Wed Feb 21 2024 03:26:02