38 #include <rviz_common/ros_integration/ros_client_abstraction.hpp>
39 #include <QApplication>
40 #include <QMessageBox>
41 #include <boost/program_options.hpp>
45 static void siginthandler(
int )
50 void usage(boost::program_options::options_description& desc,
int exit_code)
52 std::cout << desc <<
'\n';
56 int main(
int argc,
char** argv)
58 std::vector<std::string> remaining_args = rclcpp::remove_ros_arguments(argc, argv);
59 std::vector<char*> clean_argv;
60 clean_argv.reserve(remaining_args.size());
61 for (
const std::string& arg : remaining_args)
63 clean_argv.push_back(
const_cast<char*
>(arg.c_str()));
67 namespace po = boost::program_options;
71 po::options_description desc(
"Allowed options");
72 desc.add_options()(
"help,h",
"Show help message")(
"debug,g",
"Run in debug/test mode")(
73 "urdf_path,u", po::value<std::filesystem::path>(),
"Optional, path to URDF file in ROS package")(
74 "config_pkg,c", po::value<std::string>(),
"Optional, pass in existing config package to load");
81 po::store(po::parse_command_line(clean_argv.size(), &clean_argv[0], desc), vm);
87 catch (
const std::exception& e)
89 std::cerr << e.what() <<
'\n';
93 auto client = std::make_unique<rviz_common::ros_integration::RosClientAbstraction>();
94 auto node = client->init(argc, argv,
"moveit_setup_assistant",
false);
97 QApplication qt_app(argc, argv);
99 setlocale(LC_NUMERIC,
"C");
103 saw.setMinimumWidth(1090);
104 saw.setMinimumHeight(600);
109 signal(SIGINT, siginthandler);
112 const int result = qt_app.exec();
int main(int argc, char **argv)
void usage(boost::program_options::options_description &desc, int exit_code)