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 #include <qi/applicationsession.hpp>
00020 #include <qi/anymodule.hpp>
00021 #include <naoqi_driver/naoqi_driver.hpp>
00022
00023 #include <boost/program_options.hpp>
00024
00025 #include "naoqi_env.hpp"
00026 #include "helpers/driver_helpers.hpp"
00027
00028 int main(int argc, char** argv)
00029 {
00030
00031 qi::ApplicationSession app(argc, argv);
00032
00033 std::vector<std::string> args_out;
00034 ros::removeROSArgs( argc, argv, args_out );
00035
00036 namespace po = boost::program_options;
00037 po::options_description desc("Options");
00038 desc.add_options()
00039 ("help,h", "print help message")
00040 ("roscore_ip,r", po::value<std::string>(), "set the ip of the roscore to use")
00041 ("network_interface,i", po::value<std::string>()->default_value("eth0"), "set the network interface over which to connect")
00042 ("namespace,n", po::value<std::string>()->default_value("naoqi_driver_node"), "set an explicit namespace in case ROS namespace variables cannot be used");
00043
00044 po::variables_map vm;
00045 try
00046 {
00047 po::store( po::parse_command_line(argc, argv, desc), vm );
00048 }
00049 catch (boost::program_options::invalid_command_line_syntax& e)
00050 {
00051 std::cout << "error " << e.what() << std::endl;
00052 throw ros::Exception(e.what());
00053 }
00054 catch (boost::program_options::unknown_option& e)
00055 {
00056 std::cout << "error 2 " << e.what() << std::endl;
00057 throw ros::Exception(e.what());
00058 }
00059
00060 if( vm.count("help") )
00061 {
00062 std::cout << "This is the help message for the ROS-Driver C++ bridge" << std::endl << desc << std::endl;
00063 exit(0);
00064 }
00065
00066
00067
00068 #if LIBQI_VERSION>24
00069 app.startSession();
00070 #else
00071 app.start();
00072 #endif
00073 boost::shared_ptr<naoqi::Driver> bs = boost::make_shared<naoqi::Driver>(app.session(), vm["namespace"].as<std::string>());
00074
00075 app.session()->registerService("ROS-Driver", bs);
00076
00077
00078 if ( vm.count("roscore_ip") )
00079 {
00080 std::string roscore_ip = vm["roscore_ip"].as<std::string>();
00081 std::string network_interface = vm["network_interface"].as<std::string>();
00082
00083 std::cout << BOLDYELLOW << "using ip address: "
00084 << BOLDCYAN << roscore_ip << " @ " << network_interface << RESETCOLOR << std::endl;
00085 bs->init();
00086 bs->setMasterURINet( "http://"+roscore_ip+":11311", network_interface);
00087 }
00088 else
00089 {
00090 std::cout << BOLDRED << "No ip address given. Run qicli call to set the master uri" << RESETCOLOR << std::endl;
00091 bs->init();
00092 }
00093
00094 std::cout << BOLDYELLOW << "naoqi_driver initialized" << RESETCOLOR << std::endl;
00095 app.run();
00096 bs->stopService();
00097 app.session()->close();
00098 return 0;
00099 }