moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
collisions_updater.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Fraunhofer IPA
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 Fraunhofer IPA 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: Mathias Lüdtke */
36
42#include <boost/program_options.hpp>
43#include <rclcpp/logger.hpp>
44#include <rclcpp/logging.hpp>
45
46namespace po = boost::program_options;
47
48int main(int argc, char* argv[])
49{
50 std::filesystem::path config_pkg_path;
51 std::filesystem::path urdf_path;
52 std::filesystem::path srdf_path;
53 std::filesystem::path output_path;
54
55 bool include_default = false, include_always = false, keep_old = false, verbose = false;
56
57 double min_collision_fraction = 1.0;
58
59 uint32_t never_trials = 0;
60
61 // clang-format off
62 po::options_description desc("Allowed options");
63 desc.add_options()("help", "show help")("config-pkg", po::value(&config_pkg_path), "path to MoveIt config package")(
64 "urdf", po::value(&urdf_path), "path to URDF ( or xacro)")("srdf", po::value(&srdf_path),
65 "path to SRDF ( or xacro)")(
66 "output", po::value(&output_path),
67 "output path for SRDF")("xacro-args", po::value<std::vector<std::string> >()->composing(),
68 "additional arguments for xacro")("default", po::bool_switch(&include_default),
69 "disable default colliding pairs")(
70 "always", po::bool_switch(&include_always), "disable always colliding pairs")("keep", po::bool_switch(&keep_old),
71 "keep disabled link from SRDF")(
72 "verbose", po::bool_switch(&verbose), "verbose output")("trials", po::value(&never_trials),
73 "number of trials for searching never colliding pairs")(
74 "min-collision-fraction", po::value(&min_collision_fraction),
75 "fraction of small sample size to determine links that are always colliding");
76 // clang-format on
77
78 po::positional_options_description pos_desc;
79 pos_desc.add("xacro-args", -1);
80
81 po::variables_map vm;
82 po::store(po::command_line_parser(argc, argv).options(desc).positional(pos_desc).run(), vm);
83 po::notify(vm);
84
85 if (vm.count("help"))
86 {
87 std::cout << desc << '\n';
88 return 1;
89 }
90
91 rclcpp::init(argc, argv);
92 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("collision_updater");
93 moveit_setup::DataWarehousePtr config_data = std::make_shared<moveit_setup::DataWarehouse>(node);
94
96 setup_step.initialize(node, config_data);
97
98 if (!config_pkg_path.empty())
99 {
100 auto package_settings = config_data->get<moveit_setup::PackageSettingsConfig>("package_settings");
101 try
102 {
103 package_settings->loadExisting(config_pkg_path);
104 }
105 catch (const std::runtime_error& e)
106 {
107 RCLCPP_ERROR_STREAM(node->get_logger(), "Could not load config at '" << config_pkg_path << "'. " << e.what());
108 return 1;
109 }
110 }
111 else if (urdf_path.empty() || srdf_path.empty())
112 {
113 RCLCPP_ERROR_STREAM(node->get_logger(), "Please provide config package or URDF and SRDF path");
114 return 1;
115 }
116 else if (rdf_loader::RDFLoader::isXacroFile(srdf_path) && output_path.empty())
117 {
118 RCLCPP_ERROR_STREAM(node->get_logger(), "Please provide a different output file for SRDF xacro input file");
119 return 1;
120 }
121
122 auto srdf_config = config_data->get<moveit_setup::SRDFConfig>("srdf");
123
124 // overwrite config paths if applicable
125 if (!urdf_path.empty())
126 {
127 auto config = config_data->get<moveit_setup::URDFConfig>("urdf");
128
129 std::vector<std::string> xacro_args;
130 if (vm.count("xacro-args"))
131 xacro_args = vm["xacro-args"].as<std::vector<std::string> >();
132
133 config->loadFromPath(urdf_path, xacro_args);
134 }
135 if (!srdf_path.empty())
136 {
137 srdf_config->loadSRDFFile(srdf_path);
138 }
139
140 if (!keep_old)
141 {
142 srdf_config->clearCollisionData();
143 }
144
145 setup_step.startGenerationThread(never_trials, min_collision_fraction, verbose);
146 int thread_progress;
147 int last_progress = 0;
148 while ((thread_progress = setup_step.getThreadProgress()) < 100)
149 {
150 if (thread_progress - last_progress > 10)
151 {
152 RCLCPP_INFO(node->get_logger(), "%d%% complete...", thread_progress);
153 last_progress = thread_progress;
154 }
155 }
156 setup_step.joinGenerationThread();
157 RCLCPP_INFO(node->get_logger(), "100%% complete...");
158
159 size_t skip_mask = 0;
160 if (!include_default)
161 skip_mask |= (1 << moveit_setup::srdf_setup::DEFAULT);
162 if (!include_always)
163 skip_mask |= (1 << moveit_setup::srdf_setup::ALWAYS);
164
165 setup_step.linkPairsToSRDFSorted(skip_mask);
166
167 srdf_config->write(output_path.empty() ? srdf_config->getPath() : output_path);
168
169 return 0;
170}
void loadExisting(const std::string &package_path_or_name)
Method for loading the contents of the .setup_assistant file into all the configs.
void initialize(const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
Called after construction to initialize the step.
void loadFromPath(const std::filesystem::path &urdf_file_path, const std::string &xacro_args="")
Load URDF File.
void startGenerationThread(unsigned int num_trials, double min_frac, bool verbose=true)
void linkPairsToSRDFSorted(size_t skip_mask=0)
Output Link Pairs to SRDF Format; sorted; with optional filter.
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
int main(int argc, char *argv[])