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 #include <ros/ros.h>
00030 #include <QApplication>
00031 #include <string>
00032 #include <stdio.h>
00033 #include <stdlib.h>
00034 #include "MainWindow.h"
00035 #include "qt_paramedit/xmlRpcModel.h"
00036
00037 void usage(char* pname)
00038 {
00039 printf("Usage: %s [parameter root] (default: /)\n", pname);
00040 exit(1);
00041 }
00042
00043 int main(int argc, char** argv)
00044 {
00045 ros::init(argc, argv, "qt_paramedit");
00046
00047 std::string paramRoot = "/";
00048 if(argc > 1) {
00049 if(argc > 2)
00050 usage(argv[0]);
00051 paramRoot = argv[1];
00052 }
00053
00054 ros::NodeHandle nh;
00055
00056 std::string err;
00057 if(!ros::names::validate(paramRoot, err)) {
00058 ROS_FATAL("Invalid name: %s - Error: %s", paramRoot.c_str(), err.c_str());
00059 usage(argv[0]);
00060 }
00061 if(paramRoot.empty()) {
00062 ROS_FATAL("Empty param root.");
00063 usage(argv[0]);
00064 }
00065
00066 XmlRpc::XmlRpcValue xmlrpc;
00067 if(!nh.getParam(paramRoot, xmlrpc)) {
00068 ROS_FATAL("Could not get parameters at: \"%s\"", paramRoot.c_str());
00069 return 1;
00070 }
00071 if(xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00072 ROS_FATAL("Requested param root has non struct type. Can only handle dictionaries, not single parameters.");
00073 usage(argv[0]);
00074 }
00075 ROS_DEBUG("Retrieved parameters from: \"%s\"", paramRoot.c_str());
00076
00077 QApplication app(argc, argv);
00078 MainWindow gui(xmlrpc, paramRoot, &nh);
00079
00080 gui.show();
00081
00082 ros::WallRate loop(20.0);
00083 while(ros::ok() && gui.isVisible()) {
00084 ros::spinOnce();
00085
00086 app.processEvents();
00087
00088 loop.sleep();
00089 }
00090
00091 return 0;
00092 }