42 #include <boost/program_options.hpp>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
46 namespace po = boost::program_options;
48 int main(
int argc,
char* argv[])
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;
55 bool include_default =
false, include_always =
false, keep_old =
false, verbose =
false;
57 double min_collision_fraction = 1.0;
59 uint32_t never_trials = 0;
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");
78 po::positional_options_description pos_desc;
79 pos_desc.add(
"xacro-args", -1);
82 po::store(po::command_line_parser(argc, argv).
options(desc).positional(pos_desc).run(), vm);
87 std::cout << desc <<
'\n';
91 rclcpp::init(argc, argv);
92 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(
"collision_updater");
93 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"collision_updater");
94 moveit_setup::DataWarehousePtr config_data = std::make_shared<moveit_setup::DataWarehouse>(node);
99 if (!config_pkg_path.empty())
106 catch (
const std::runtime_error& e)
108 RCLCPP_ERROR_STREAM(LOGGER,
"Could not load config at '" << config_pkg_path <<
"'. " << e.what());
112 else if (urdf_path.empty() || srdf_path.empty())
114 RCLCPP_ERROR_STREAM(LOGGER,
"Please provide config package or URDF and SRDF path");
119 RCLCPP_ERROR_STREAM(LOGGER,
"Please provide a different output file for SRDF xacro input file");
126 if (!urdf_path.empty())
130 std::vector<std::string> xacro_args;
131 if (vm.count(
"xacro-args"))
132 xacro_args = vm[
"xacro-args"].as<std::vector<std::string> >();
136 if (!srdf_path.empty())
138 srdf_config->loadSRDFFile(srdf_path);
143 srdf_config->clearCollisionData();
148 int last_progress = 0;
151 if (thread_progress - last_progress > 10)
153 RCLCPP_INFO(LOGGER,
"%d%% complete...", thread_progress);
154 last_progress = thread_progress;
158 RCLCPP_INFO(LOGGER,
"100%% complete...");
160 size_t skip_mask = 0;
161 if (!include_default)
168 srdf_config->write(output_path.empty() ? srdf_config->getPath() : output_path);
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)
int getThreadProgress() const
void joinGenerationThread()
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[])