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