logger_level_panel.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "logger_level_panel.h"
00031 
00032 #include <ros/ros.h>
00033 #include <roscpp/GetLoggers.h>
00034 #include <roscpp/SetLoggerLevel.h>
00035 
00036 #include <wx/event.h>
00037 #include <wx/msgdlg.h>
00038 
00039 #include <algorithm>
00040 
00041 namespace rxtools
00042 {
00043 
00044 LoggerLevelPanel::LoggerLevelPanel(wxWindow* parent, int id, wxPoint pos, wxSize size, int style)
00045 : LoggerLevelPanelBase(parent, id, pos, size, style)
00046 , connected_(true)
00047 , shutdown_thread_(false)
00048 , RECONNECTED_TO_MASTER_EVENT_(wxNewEventType())
00049 , DISCONNECTED_FROM_MASTER_EVENT_(wxNewEventType())
00050 {
00051   Connect(RECONNECTED_TO_MASTER_EVENT_, (wxObjectEventFunction)&LoggerLevelPanel::onMasterReconnected, 0, this);
00052   Connect(DISCONNECTED_FROM_MASTER_EVENT_, (wxObjectEventFunction)&LoggerLevelPanel::onMasterDisconnected, 0, this);
00053   check_master_thread_ = new boost::thread(boost::bind(&LoggerLevelPanel::checkForMaster, this));
00054 
00055   fillNodeList();
00056 }
00057 
00058 LoggerLevelPanel::~LoggerLevelPanel()
00059 {
00060   shutdown_thread_ = true;
00061   check_master_thread_->join();
00062   delete check_master_thread_;
00063 }
00064 
00065 void LoggerLevelPanel::fillNodeList()
00066 {
00067   nodes_box_->Clear();
00068 
00069   ros::V_string nodes;
00070   ros::master::getNodes(nodes);
00071 
00072   std::sort(nodes.begin(), nodes.end());
00073 
00074   ros::V_string::iterator it = nodes.begin();
00075   ros::V_string::iterator end = nodes.end();
00076   for (; it != end; ++it)
00077   {
00078     const std::string& node = *it;
00079 
00080     std::string error;
00081     if (!ros::names::validate(node, error))
00082     {
00083       ROS_ERROR("Node [%s] has an invalid name", node.c_str());
00084       continue;
00085     }
00086 
00087     if (ros::service::exists(node + "/get_loggers", false))
00088     {
00089       nodes_box_->Append(wxString::FromAscii(node.c_str()));
00090     }
00091   }
00092 }
00093 
00094 void LoggerLevelPanel::refresh()
00095 {
00096   fillNodeList();
00097 }
00098 
00099 void LoggerLevelPanel::onNodesRefresh( wxCommandEvent& event )
00100 {
00101   fillNodeList();
00102 }
00103 
00104 void LoggerLevelPanel::onNodeSelected( wxCommandEvent& event )
00105 {
00106   loggers_box_->Clear();
00107   levels_box_->Clear();
00108   loggers_.clear();
00109 
00110   std::string node = (const char*)nodes_box_->GetStringSelection().fn_str();
00111   if (node.empty())
00112   {
00113     return;
00114   }
00115 
00116   roscpp::GetLoggers srv;
00117   if (ros::service::call(node + "/get_loggers", srv))
00118   {
00119     std::vector<roscpp::Logger>::iterator it = srv.response.loggers.begin();
00120     std::vector<roscpp::Logger>::iterator end = srv.response.loggers.end();
00121     for (; it != end; ++it)
00122     {
00123       roscpp::Logger& logger = *it;
00124       const std::string& name = logger.name;
00125 
00126       loggers_[name] = logger.level;
00127 
00128       loggers_box_->Append(wxString::FromAscii(name.c_str()));
00129     }
00130   }
00131   else
00132   {
00133     wxString msg;
00134     msg.Printf(wxT("Failed to call service [%s/get_loggers].  Did the node go away?"), wxString::FromAscii(node.c_str()).c_str());
00135     wxMessageBox(msg, wxT("Failed to lookup loggers"), wxOK|wxICON_ERROR);
00136   }
00137 }
00138 
00139 void LoggerLevelPanel::onLoggerSelected( wxCommandEvent& event )
00140 {
00141   levels_box_->Clear();
00142 
00143   std::string logger = (const char*)loggers_box_->GetStringSelection().fn_str();
00144   if (logger.empty())
00145   {
00146     return;
00147   }
00148 
00149   M_string::iterator it = loggers_.find(logger);
00150   std::string level = it->second;
00151 
00152   std::transform(level.begin(), level.end(), level.begin(), (int(*)(int))std::toupper);
00153 
00154   int selection = 0;
00155   if (level == "DEBUG")
00156   {
00157     selection = 0;
00158   }
00159   else if (level == "INFO")
00160   {
00161     selection = 1;
00162   }
00163   else if (level == "WARN")
00164   {
00165     selection = 2;
00166   }
00167   else if (level == "ERROR")
00168   {
00169     selection = 3;
00170   }
00171   else if (level == "FATAL")
00172   {
00173     selection = 4;
00174   }
00175   else
00176   {
00177     ROS_ERROR("Unknown logger level [%s]", level.c_str());
00178     selection = -1;
00179   }
00180 
00181   levels_box_->Append(wxT("Debug"));
00182   levels_box_->Append(wxT("Info"));
00183   levels_box_->Append(wxT("Warn"));
00184   levels_box_->Append(wxT("Error"));
00185   levels_box_->Append(wxT("Fatal"));
00186   levels_box_->SetSelection(selection);
00187 }
00188 
00189 void LoggerLevelPanel::onLevelSelected( wxCommandEvent& event )
00190 {
00191   std::string level = (const char*)levels_box_->GetStringSelection().fn_str();
00192   if (level.empty())
00193   {
00194     return;
00195   }
00196 
00197   std::string node = (const char*)nodes_box_->GetStringSelection().fn_str();
00198   std::string logger = (const char*)loggers_box_->GetStringSelection().fn_str();
00199 
00200   roscpp::SetLoggerLevel srv;
00201   srv.request.logger = logger;
00202   srv.request.level = level;
00203   if (!ros::service::call(node + "/set_logger_level", srv))
00204   {
00205     wxString msg;
00206     msg.Printf(wxT("Failed to call service [%s/set_logger_level].  Did the node go away?"), wxString::FromAscii(node.c_str()).c_str());
00207     wxMessageBox(msg, wxT("Failed to set logger level"), wxOK|wxICON_ERROR);
00208   }
00209   else
00210   {
00211     loggers_[logger] = level;
00212   }
00213 }
00214 
00215 void LoggerLevelPanel::checkForMaster()
00216 {
00217   while (!shutdown_thread_)
00218   {
00219     if (ros::master::check())
00220     {
00221       if (!connected_)
00222       {
00223         connected_ = true;
00224         ROS_INFO("Reconnected to ROS master");
00225         wxCommandEvent event(RECONNECTED_TO_MASTER_EVENT_);
00226         wxPostEvent(this, event);
00227       }
00228     }
00229     else if (connected_)
00230     {
00231       connected_ = false;
00232       ROS_INFO("Disconnected from ROS master");
00233       wxCommandEvent event(DISCONNECTED_FROM_MASTER_EVENT_);
00234       wxPostEvent(this, event);
00235     }
00236     boost::this_thread::sleep(boost::posix_time::milliseconds(500));
00237   }
00238 }
00239 
00240 void LoggerLevelPanel::onMasterReconnected(wxEvent& event)
00241 {
00242   Enable(1);
00243   fillNodeList();
00244 }
00245 
00246 void LoggerLevelPanel::onMasterDisconnected(wxEvent& event)
00247 {
00248   Enable(0);
00249 }
00250 
00251 } // namespace rxtools


rxtools
Author(s): Josh Faust, Rob Wheeler, Ken Conley
autogenerated on Mon Oct 6 2014 07:25:59