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
00033
00034
00035
00036
00037 #include "widgets/setup_assistant_widget.h"
00038 #include <ros/ros.h>
00039 #include <QApplication>
00040 #include <QMessageBox>
00041 #include <boost/program_options.hpp>
00042 #include <signal.h>
00043 #include <locale.h>
00044
00045 static void siginthandler(int param)
00046 {
00047 QApplication::quit();
00048 }
00049
00050 void usage(boost::program_options::options_description& desc, int exit_code)
00051 {
00052 std::cout << desc << std::endl;
00053 exit(exit_code);
00054 }
00055
00056 int main(int argc, char** argv)
00057 {
00058
00059 namespace po = boost::program_options;
00060
00061
00062 po::options_description desc("Allowed options");
00063 desc.add_options()("help,h", "Show help message")("debug,g", "Run in debug/test mode")(
00064 "urdf_path,u", po::value<std::string>(), "Optional, path to URDF file in ROS package")(
00065 "config_pkg,c", po::value<std::string>(), "Optional, pass in existing config package to load");
00066
00067
00068 po::variables_map vm;
00069 try
00070 {
00071 po::store(po::parse_command_line(argc, argv, desc), vm);
00072 po::notify(vm);
00073
00074 if (vm.count("help"))
00075 usage(desc, 0);
00076 }
00077 catch (const std::exception& e)
00078 {
00079 std::cerr << e.what() << std::endl;
00080 usage(desc, 1);
00081 }
00082
00083 ros::init(argc, argv, "moveit_setup_assistant", ros::init_options::NoSigintHandler);
00084
00085
00086 ros::AsyncSpinner spinner(1);
00087 spinner.start();
00088
00089 ros::NodeHandle nh;
00090
00091
00092 QApplication qtApp(argc, argv);
00093
00094 setlocale(LC_NUMERIC, "C");
00095
00096
00097 moveit_setup_assistant::SetupAssistantWidget saw(NULL, vm);
00098 saw.setMinimumWidth(980);
00099 saw.setMinimumHeight(550);
00100
00101
00102 saw.show();
00103
00104 signal(SIGINT, siginthandler);
00105
00106
00107 const int result = qtApp.exec();
00108
00109
00110 ros::shutdown();
00111
00112 return result;
00113 }