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
00034 #include <wx/app.h>
00035 #include <wx/timer.h>
00036 #include "visualization_frame.h"
00037 #include "generated/rviz_generated.h"
00038 #include "wx_log_rosout.h"
00039 #include <ogre_tools/initialization.h>
00040
00041 #include <ros/ros.h>
00042
00043 #include <boost/thread.hpp>
00044 #include <boost/program_options.hpp>
00045 #include <signal.h>
00046
00047 #include <OGRE/OgreHighLevelGpuProgramManager.h>
00048 #include <std_srvs/Empty.h>
00049
00050 #ifdef __WXMAC__
00051 #include <ApplicationServices/ApplicationServices.h>
00052
00053
00054 #undef check
00055 #endif
00056
00057
00058 namespace po = boost::program_options;
00059
00060 namespace rviz
00061 {
00062
00063 bool reloadShaders(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00064 {
00065 Ogre::ResourceManager::ResourceMapIterator it = Ogre::HighLevelGpuProgramManager::getSingleton().getResourceIterator();
00066 while (it.hasMoreElements())
00067 {
00068 Ogre::ResourcePtr resource = it.getNext();
00069 resource->reload();
00070 }
00071 return true;
00072 }
00073
00074 class WaitForMasterDialog : public WaitForMasterDialogGenerated
00075 {
00076 public:
00077 WaitForMasterDialog(wxWindow* parent)
00078 : WaitForMasterDialogGenerated(parent, wxID_ANY)
00079 , timer_(this)
00080 {
00081 Connect(timer_.GetId(), wxEVT_TIMER, wxTimerEventHandler(WaitForMasterDialog::onTimer), NULL, this);
00082 timer_.Start(1000);
00083
00084 const std::string& master_uri = ros::master::getURI();
00085 std::stringstream ss;
00086 ss << "Could not contact ROS master at [" << master_uri << "], retrying...";
00087 text_->SetLabel(wxString::FromAscii(ss.str().c_str()));
00088 Fit();
00089 }
00090
00091 void onTimer(wxTimerEvent&)
00092 {
00093 if (ros::master::check())
00094 {
00095 EndModal(wxID_OK);
00096 }
00097 }
00098
00099 void onCancel(wxCommandEvent&)
00100 {
00101 EndModal(wxID_CANCEL);
00102 }
00103
00104 void onClose(wxCloseEvent&)
00105 {
00106 EndModal(wxID_CANCEL);
00107 }
00108
00109 private:
00110 wxTimer timer_;
00111 };
00112
00113 class VisualizerApp : public wxApp
00114 {
00115 public:
00116 char** local_argv_;
00117 VisualizationFrame* frame_;
00118 volatile bool continue_;
00119 boost::thread signal_handler_thread_;
00120 wxTimer timer_;
00121 ros::NodeHandlePtr nh_;
00122 ros::ServiceServer reload_shaders_service_;
00123
00124 VisualizerApp()
00125 : timer_(this)
00126 {
00127 }
00128
00129 void onTimer(wxTimerEvent&)
00130 {
00131 if (!continue_)
00132 {
00133 frame_->Close();
00134 }
00135 }
00136
00137 bool OnInit()
00138 {
00139 #ifdef __WXMAC__
00140 ProcessSerialNumber PSN;
00141 GetCurrentProcess(&PSN);
00142 TransformProcessType(&PSN,kProcessTransformToForegroundApplication);
00143 SetFrontProcess(&PSN);
00144 #endif
00145
00146 wxLog::SetActiveTarget(new wxLogRosout());
00147 try
00148 {
00149
00150
00151 local_argv_ = new char*[ argc ];
00152 for ( int i = 0; i < argc; ++i )
00153 {
00154 local_argv_[ i ] = strdup( wxString( argv[ i ] ).mb_str() );
00155 }
00156
00157 ros::init(argc, local_argv_, "rviz", ros::init_options::AnonymousName | ros::init_options::NoSigintHandler);
00158
00159 po::options_description options;
00160 options.add_options()
00161 ("help,h", "Produce this help message")
00162 ("display-config,d", po::value<std::string>(), "A display config file (.vcg) to load")
00163 ("target-frame,t", po::value<std::string>(), "Set the target frame")
00164 ("fixed-frame,f", po::value<std::string>(), "Set the fixed frame")
00165 ("ogre-log,l", "Enable the Ogre.log file (output in cwd)");
00166 po::variables_map vm;
00167 std::string display_config, target_frame, fixed_frame;
00168 bool enable_ogre_log = false;
00169 try
00170 {
00171 po::store(po::parse_command_line(argc, local_argv_, options), vm);
00172 po::notify(vm);
00173
00174 if (vm.count("help"))
00175 {
00176 std::cout << "rviz command line options:\n" << options;
00177 return false;
00178 }
00179
00180
00181 if (vm.count("display-config"))
00182 {
00183 display_config = vm["display-config"].as<std::string>();
00184 }
00185
00186 if (vm.count("target-frame"))
00187 {
00188 target_frame = vm["target-frame"].as<std::string>();
00189 }
00190
00191 if (vm.count("fixed-frame"))
00192 {
00193 fixed_frame = vm["fixed-frame"].as<std::string>();
00194 }
00195
00196 if (vm.count("ogre-log"))
00197 {
00198 enable_ogre_log = true;
00199 }
00200 }
00201 catch (std::exception& e)
00202 {
00203 ROS_ERROR("Error parsing command line: %s", e.what());
00204 return false;
00205 }
00206
00207 if (!ros::master::check())
00208 {
00209 WaitForMasterDialog d(0);
00210 if (d.ShowModal() != wxID_OK)
00211 {
00212 return false;
00213 }
00214 }
00215
00216
00217
00218 sigset_t sig_set;
00219 sigemptyset(&sig_set);
00220 sigaddset(&sig_set, SIGKILL);
00221 sigaddset(&sig_set, SIGTERM);
00222 sigaddset(&sig_set, SIGQUIT);
00223 sigaddset(&sig_set, SIGINT);
00224 pthread_sigmask(SIG_BLOCK, &sig_set, NULL);
00225
00226
00227 continue_ = true;
00228 signal_handler_thread_ = boost::thread(boost::bind(&VisualizerApp::signalHandler, this));
00229
00230 nh_.reset(new ros::NodeHandle);
00231 ogre_tools::initializeOgre(enable_ogre_log);
00232
00233 frame_ = new VisualizationFrame(NULL);
00234 frame_->initialize(display_config, fixed_frame, target_frame);
00235
00236 SetTopWindow(frame_);
00237 frame_->Show();
00238
00239 Connect(timer_.GetId(), wxEVT_TIMER, wxTimerEventHandler(VisualizerApp::onTimer), NULL, this);
00240 timer_.Start(100);
00241
00242 ros::NodeHandle private_nh("~");
00243 reload_shaders_service_ = private_nh.advertiseService("reload_shaders", reloadShaders);
00244
00245 }
00246 catch (std::exception& e)
00247 {
00248 ROS_ERROR("Caught exception while loading: %s", e.what());
00249 return false;
00250 }
00251
00252 return true;
00253 }
00254
00255 int OnExit()
00256 {
00257 timer_.Stop();
00258 continue_ = false;
00259
00260 raise(SIGQUIT);
00261
00262 signal_handler_thread_.join();
00263
00264 for ( int i = 0; i < argc; ++i )
00265 {
00266 free( local_argv_[ i ] );
00267 }
00268 delete [] local_argv_;
00269
00270 ogre_tools::cleanupOgre();
00271
00272 return 0;
00273 }
00274
00275 void signalHandler()
00276 {
00277 sigset_t signal_set;
00278 while(continue_)
00279 {
00280
00281 sigfillset(&signal_set);
00282
00283 #if defined(__WXMAC__)
00284 int sig;
00285 sigwait(&signal_set, &sig);
00286 #else
00287 struct timespec ts = {0, 100000000};
00288 int sig = sigtimedwait(&signal_set, NULL, &ts);
00289 #endif
00290
00291 switch( sig )
00292 {
00293 case SIGKILL:
00294 case SIGTERM:
00295 case SIGQUIT:
00296 {
00297 exit(1);
00298 }
00299 break;
00300
00301 case SIGINT:
00302 {
00303 ros::shutdown();
00304 continue_ = false;
00305 return;
00306 }
00307 break;
00308
00309 default:
00310 break;
00311 }
00312 }
00313 }
00314 };
00315
00316 DECLARE_APP(VisualizerApp);
00317
00318 }
00319
00320
00321 IMPLEMENT_APP(rviz::VisualizerApp);