Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include "widgets/setup_assistant_widget.h"
00033 #include <ros/ros.h>
00034 #include <QApplication>
00035 #include <QMessageBox>
00036 #include <boost/program_options.hpp>
00037 #include <signal.h>
00038
00039 static void siginthandler(int param)
00040 {
00041 QApplication::quit();
00042 }
00043
00044 int main(int argc, char **argv)
00045 {
00046
00047 namespace po = boost::program_options;
00048
00049
00050 po::options_description desc("Allowed options");
00051 desc.add_options()
00052 ("help", "Show help message")
00053 ("debug", "Run in debug/test mode")
00054 ("urdf_path", po::value<std::string>(), "Optional, relative path to URDF in URDF package")
00055 ("config_pkg", po::value<std::string>(), "Optional, pass in existing config package to load");
00056
00057
00058 po::variables_map vm;
00059 po::store(po::parse_command_line(argc, argv, desc), vm);
00060 po::notify(vm);
00061
00062 if (vm.count("help"))
00063 {
00064 std::cout << desc << std::endl;
00065 return 1;
00066 }
00067
00068
00069 ros::init(argc, argv, "moveit_setup_assistant", ros::init_options::NoSigintHandler);
00070
00071
00072 ros::AsyncSpinner spinner(1);
00073 spinner.start();
00074
00075 ros::NodeHandle nh;
00076
00077
00078 QApplication qtApp(argc, argv);
00079
00080
00081 moveit_setup_assistant::SetupAssistantWidget saw( NULL, vm );
00082 saw.setMinimumWidth(1024);
00083 saw.setMinimumHeight(768);
00084
00085
00086 saw.show();
00087
00088 signal(SIGINT, siginthandler);
00089
00090
00091 const int result = qtApp.exec();
00092
00093
00094 ros::shutdown();
00095
00096 return result;
00097 }