Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <tf/transform_listener.h>
00003 #include "geometryPosesCreatorGui.h"
00004 #include <string>
00005 #include <QApplication>
00006
00007 int main(int argc, char** argv)
00008 {
00009 ros::init(argc, argv, "geometry_poses_creator_gui");
00010
00011 if(argc != 3) {
00012 ROS_FATAL("Usage: %s fixed_frame target_frame", argv[0]);
00013 return 1;
00014 }
00015
00016 std::string fixed_frame = argv[1];
00017 std::string target_frame = argv[2];
00018
00019 ros::NodeHandle nh;
00020
00021 QApplication app(argc, argv);
00022 GeometryPosesCreatorGui gui(fixed_frame, target_frame);
00023 gui.show();
00024
00025 ros::WallRate rate(10);
00026 while(ros::ok() && gui.isVisible()) {
00027 ros::spinOnce();
00028
00029 app.processEvents();
00030
00031 rate.sleep();
00032 }
00033
00034 return 0;
00035 }