$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 ********************************************************************/ 00034 00035 #include "rosout_panel.h" 00036 #include "rosout_setup_dialog.h" 00037 #include "rosout_list_control.h" 00038 00039 #include <wx/wx.h> 00040 #include <wx/artprov.h> 00041 00042 #include <ros/ros.h> 00043 #include <ros/package.h> 00044 00045 #include <sstream> 00046 #include <algorithm> 00047 00048 #include <boost/bind.hpp> 00049 00050 #include "rosout_text_filter.h" 00051 #include "rosout_text_filter_control.h" 00052 #include "rosout_severity_filter.h" 00053 #include "rosout_severity_filter_control.h" 00054 00055 namespace rxtools 00056 { 00057 00058 RosoutPanel::RosoutPanel(wxWindow* parent, int id, wxPoint pos, wxSize size, int style) 00059 : RosoutPanelBase(parent, id, pos, size, style) 00060 , enabled_(false) 00061 , message_id_counter_(0) 00062 , max_messages_(20000) 00063 , needs_refilter_(false) 00064 , refilter_timer_(0.0f) 00065 , pause_(false) 00066 , logger_level_frame_(0) 00067 { 00068 wxInitAllImageHandlers(); 00069 00070 nh_.setCallbackQueue(&callback_queue_); 00071 00072 process_timer_ = new wxTimer(this); 00073 process_timer_->Start(250); 00074 00075 Connect(process_timer_->GetId(), wxEVT_TIMER, wxTimerEventHandler(RosoutPanel::onProcessTimer), NULL, this); 00076 00077 table_->setModel(this); 00078 00079 setTopic("/rosout_agg"); 00080 setEnabled(true); 00081 00082 std::string icon_path = ros::package::getPath(ROS_PACKAGE_NAME) + "/icons/"; 00083 delete_filter_bitmap_ = wxBitmap(wxString::FromAscii((icon_path + "delete-filter-16.png").c_str()), wxBITMAP_TYPE_PNG); 00084 00085 wxBitmap add_bitmap(wxString::FromAscii((icon_path + "add-16.png").c_str()), wxBITMAP_TYPE_PNG); 00086 add_filter_button_->SetBitmapLabel(add_bitmap); 00087 00088 add_filter_button_->Connect(wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(RosoutPanel::onAddFilterPressed), NULL, this); 00089 00090 { 00091 RosoutSeverityFilterPtr filter(new RosoutSeverityFilter); 00092 RosoutSeverityFilterControl* control = new RosoutSeverityFilterControl(this, filter); 00093 severity_filter_ = filter; 00094 severity_sizer_->Add(control, 0, wxEXPAND); 00095 severity_filter_->getChangedSignal().connect(boost::bind(&RosoutPanel::onFilterChanged, this, _1)); 00096 } 00097 00098 createTextFilter(); 00099 00100 filters_window_->SetMinSize(wxSize(-1, filters_[0].panel->GetSize().GetHeight() + add_filter_button_->GetSize().GetHeight() + 5)); 00101 } 00102 00103 RosoutPanel::~RosoutPanel() 00104 { 00105 unsubscribe(); 00106 00107 Disconnect(process_timer_->GetId(), wxEVT_TIMER, wxTimerEventHandler(RosoutPanel::onProcessTimer), NULL, this); 00108 00109 delete process_timer_; 00110 00111 clear(); 00112 } 00113 00114 void RosoutPanel::clear() 00115 { 00116 table_->SetItemCount(0); 00117 messages_.clear(); 00118 ordered_messages_.clear(); 00119 } 00120 00121 void RosoutPanel::setEnabled(bool enabled) 00122 { 00123 if (enabled_ == enabled) 00124 { 00125 return; 00126 } 00127 00128 enabled_ = enabled; 00129 if (enabled) 00130 { 00131 subscribe(); 00132 } 00133 else 00134 { 00135 unsubscribe(); 00136 } 00137 } 00138 00139 void RosoutPanel::subscribe() 00140 { 00141 if (!enabled_ || topic_.empty()) 00142 { 00143 return; 00144 } 00145 00146 sub_ = nh_.subscribe(topic_, 0, &RosoutPanel::incomingMessage, this); 00147 } 00148 00149 void RosoutPanel::unsubscribe() 00150 { 00151 sub_.shutdown(); 00152 } 00153 00154 void RosoutPanel::setTopic(const std::string& topic) 00155 { 00156 if (topic == topic_) 00157 { 00158 return; 00159 } 00160 00161 unsubscribe(); 00162 00163 topic_ = topic; 00164 00165 subscribe(); 00166 } 00167 00168 void RosoutPanel::setMessages(const M_IdToMessage& messages) 00169 { 00170 messages_ = messages; 00171 00172 if (messages.empty()) 00173 { 00174 message_id_counter_ = 0; 00175 } 00176 else 00177 { 00178 message_id_counter_ = messages.rbegin()->first; 00179 } 00180 00181 refilter(); 00182 } 00183 00184 RosoutFrame* RosoutPanel::createNewFrame() 00185 { 00186 RosoutFrame* frame = new RosoutFrame(0); 00187 frame->rosout_panel_->setMessages(messages_); 00188 frame->Show(); 00189 frame->Raise(); 00190 00191 return frame; 00192 } 00193 00194 void RosoutPanel::onNewWindow(wxCommandEvent& event) 00195 { 00196 createNewFrame(); 00197 } 00198 00199 void RosoutPanel::onLoggerLevelsClose(wxCloseEvent& event) 00200 { 00201 logger_level_frame_->Show(false); 00202 event.Veto(); 00203 } 00204 00205 void RosoutPanel::onLoggerLevels(wxCommandEvent& event) 00206 { 00207 if (!logger_level_frame_) 00208 { 00209 logger_level_frame_ = new LoggerLevelFrame(this); 00210 logger_level_frame_->Connect(wxEVT_CLOSE_WINDOW, wxCloseEventHandler(RosoutPanel::onLoggerLevelsClose), NULL, this); 00211 } 00212 00213 logger_level_frame_->Show(); 00214 logger_level_frame_->Raise(); 00215 } 00216 00217 bool filterEnabledCheckboxEqual(wxWindowID id, const RosoutPanel::FilterInfo& info) 00218 { 00219 return info.enabled_cb && info.enabled_cb->GetId() == id; 00220 } 00221 00222 void RosoutPanel::onFilterEnableChecked(wxCommandEvent& event) 00223 { 00224 V_FilterInfo::iterator it = std::find_if(filters_.begin(), filters_.end(), boost::bind(filterEnabledCheckboxEqual, event.GetId(), _1)); 00225 if (it != filters_.end()) 00226 { 00227 FilterInfo& info = *it; 00228 info.filter->setEnabled(event.IsChecked()); 00229 refilter(); 00230 } 00231 } 00232 00233 bool filterDeleteButtonEqual(wxWindowID id, const RosoutPanel::FilterInfo& info) 00234 { 00235 return info.delete_button && info.delete_button->GetId() == id; 00236 } 00237 00238 void RosoutPanel::onFilterDelete(wxCommandEvent& event) 00239 { 00240 V_FilterInfo::iterator it = std::find_if(filters_.begin(), filters_.end(), boost::bind(filterDeleteButtonEqual, event.GetId(), _1)); 00241 if (it != filters_.end()) 00242 { 00243 FilterInfo& info = *it; 00244 removeFilter(info.filter); 00245 } 00246 } 00247 00248 bool filterUpButtonEqual(wxWindowID id, const RosoutPanel::FilterInfo& info) 00249 { 00250 return info.up_button && info.up_button->GetId() == id; 00251 } 00252 00253 void RosoutPanel::onFilterMoveUp(wxCommandEvent& event) 00254 { 00255 V_FilterInfo::iterator it = std::find_if(filters_.begin(), filters_.end(), boost::bind(filterUpButtonEqual, event.GetId(), _1)); 00256 if (it != filters_.end() && it != filters_.begin()) 00257 { 00258 FilterInfo& info = *it; 00259 00260 filters_sizer_->Detach(info.panel); 00261 size_t new_index = it - filters_.begin() - 1; 00262 filters_sizer_->Insert(new_index, info.panel, 0, wxEXPAND|wxBOTTOM, 1); 00263 filters_sizer_->Layout(); 00264 std::swap(*it, *(it - 1)); 00265 00266 resizeFiltersPane(); 00267 updateFilterBackgrounds(); 00268 } 00269 } 00270 00271 bool filterDownButtonEqual(wxWindowID id, const RosoutPanel::FilterInfo& info) 00272 { 00273 return info.down_button && info.down_button->GetId() == id; 00274 } 00275 00276 void RosoutPanel::onFilterMoveDown(wxCommandEvent& event) 00277 { 00278 V_FilterInfo::iterator it = std::find_if(filters_.begin(), filters_.end(), boost::bind(filterDownButtonEqual, event.GetId(), _1)); 00279 if (it != filters_.end() && it != filters_.end() - 1) 00280 { 00281 FilterInfo& info = *it; 00282 00283 filters_sizer_->Detach(info.panel); 00284 size_t new_index = it - filters_.begin() + 1; 00285 filters_sizer_->Insert(new_index, info.panel, 0, wxEXPAND|wxBOTTOM, 1); 00286 filters_sizer_->Layout(); 00287 std::swap(*it, *(it + 1)); 00288 00289 resizeFiltersPane(); 00290 updateFilterBackgrounds(); 00291 } 00292 } 00293 00294 void RosoutPanel::updateFilterBackgrounds() 00295 { 00296 for (size_t i = 0; i < filters_.size(); ++i) 00297 { 00298 FilterInfo& info = filters_[i]; 00299 if (i % 2 == 0) 00300 { 00301 info.panel->SetBackgroundColour(*wxLIGHT_GREY); 00302 info.control->SetBackgroundColour(*wxLIGHT_GREY); 00303 } 00304 else 00305 { 00306 info.panel->SetBackgroundColour(wxNullColour); 00307 info.control->SetBackgroundColour(wxNullColour); 00308 } 00309 } 00310 } 00311 00312 void RosoutPanel::addFilter(const RosoutFilterPtr& filter, wxWindow* control) 00313 { 00314 table_->preItemChanges(); 00315 00316 FilterInfo info; 00317 info.filter = filter; 00318 info.control = control; 00319 00320 info.panel = new wxPanel(filters_window_, wxID_ANY); 00321 filters_sizer_->Add(info.panel, 0, wxEXPAND|wxBOTTOM, 1); 00322 info.panel->SetPosition(wxPoint(0, info.panel->GetSize().GetHeight() * filters_.size())); 00323 00324 if (filters_.size() % 2 == 0) 00325 { 00326 info.panel->SetBackgroundColour(*wxLIGHT_GREY); 00327 info.control->SetBackgroundColour(*wxLIGHT_GREY); 00328 } 00329 else 00330 { 00331 info.panel->SetBackgroundColour(wxNullColour); 00332 info.control->SetBackgroundColour(wxNullColour); 00333 } 00334 00335 control->Reparent(info.panel); 00336 00337 info.sizer = new wxBoxSizer(wxHORIZONTAL); 00338 info.panel->SetSizer(info.sizer); 00339 00340 00341 #if 01 00342 //if (disableable) 00343 { 00344 info.enabled_cb = new wxCheckBox(info.panel, wxID_ANY, wxT("Enabled")); 00345 info.enabled_cb->SetValue(filter->isEnabled()); 00346 info.sizer->Add(info.enabled_cb, 0, wxALIGN_CENTER_VERTICAL); 00347 info.enabled_cb->Connect(wxEVT_COMMAND_CHECKBOX_CLICKED, wxCommandEventHandler(RosoutPanel::onFilterEnableChecked), NULL, this); 00348 } 00349 #endif 00350 00351 info.sizer->Add(control, 1, wxALIGN_CENTER_VERTICAL); 00352 00353 info.delete_button = 0; 00354 //if (removable) 00355 { 00356 info.delete_button = new wxBitmapButton(info.panel, wxID_ANY, delete_filter_bitmap_); 00357 info.sizer->Add(info.delete_button, 0, wxALIGN_CENTER_VERTICAL); 00358 info.delete_button->Connect(wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(RosoutPanel::onFilterDelete), NULL, this); 00359 00360 info.down_button = new wxBitmapButton(info.panel, wxID_ANY, wxArtProvider::GetBitmap(wxART_GO_DOWN, wxART_OTHER, wxSize(16, 16))); 00361 info.sizer->Add(info.down_button, 0, wxALIGN_CENTER_VERTICAL); 00362 info.down_button->Connect(wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(RosoutPanel::onFilterMoveDown), NULL, this); 00363 00364 info.up_button = new wxBitmapButton(info.panel, wxID_ANY, wxArtProvider::GetBitmap(wxART_GO_UP, wxART_OTHER, wxSize(16, 16))); 00365 info.sizer->Add(info.up_button, 0, wxALIGN_CENTER_VERTICAL); 00366 info.up_button->Connect(wxEVT_COMMAND_BUTTON_CLICKED, wxCommandEventHandler(RosoutPanel::onFilterMoveUp), NULL, this); 00367 } 00368 00369 filters_.push_back(info); 00370 00371 resizeFiltersPane(); 00372 00373 filters_window_->Scroll(-1, 100000); 00374 00375 filter->getChangedSignal().connect(boost::bind(&RosoutPanel::onFilterChanged, this, _1)); 00376 00377 needs_refilter_ = true; 00378 00379 table_->postItemChanges(); 00380 } 00381 00382 void RosoutPanel::resizeFiltersPane() 00383 { 00384 filters_window_->Layout(); 00385 00386 wxSize sizer_size = filters_window_->GetSizer()->GetMinSize(); 00387 if (sizer_size.GetHeight() > 150) 00388 { 00389 filters_window_->SetMinSize(wxSize(-1, 150)); 00390 filters_window_->GetSizer()->FitInside(filters_window_); 00391 } 00392 else 00393 { 00394 filters_window_->SetMinSize(wxSize(-1, sizer_size.GetHeight())); 00395 } 00396 00397 Layout(); 00398 Refresh(); 00399 } 00400 00401 bool filterEquals(const RosoutFilterPtr& filter, const RosoutPanel::FilterInfo& info) 00402 { 00403 return info.filter == filter; 00404 } 00405 00406 void RosoutPanel::removeFilter(const RosoutFilterPtr& filter) 00407 { 00408 V_FilterInfo::iterator it = std::find_if(filters_.begin(), filters_.end(), boost::bind(filterEquals, filter, _1)); 00409 if (it != filters_.end()) 00410 { 00411 FilterInfo& info = *it; 00412 info.panel->Destroy(); 00413 filters_.erase(it); 00414 00415 resizeFiltersPane(); 00416 updateFilterBackgrounds(); 00417 00418 refilter(); 00419 } 00420 } 00421 00422 void RosoutPanel::clearFilters() 00423 { 00424 while (!filters_.empty()) 00425 { 00426 removeFilter(filters_.front().filter); 00427 } 00428 } 00429 00430 void RosoutPanel::onFilterChanged(const RosoutFilter*) 00431 { 00432 needs_refilter_ = true; 00433 } 00434 00435 template<class T> 00436 void printStuff(const std::string& name, T* win) 00437 { 00438 wxPoint point = win->GetPosition(); 00439 wxSize size = win->GetSize(); 00440 ROS_INFO("%s: x: %d, y: %d, w: %d, h: %d", name.c_str(), point.x, point.y, size.GetWidth(), size.GetHeight()); 00441 } 00442 00443 #define PRINT_STUFF(description) \ 00444 ROS_INFO(description); \ 00445 printStuff(" filters_sizer_", filters_sizer_); \ 00446 printStuff(" filters_window_->GetSizer()", filters_window_->GetSizer()); \ 00447 printStuff(" filters_window_", filters_window_); \ 00448 for (size_t i = 0; i < filters_.size(); ++i) \ 00449 { \ 00450 { \ 00451 std::stringstream ss; \ 00452 ss << " panel " << i; \ 00453 printStuff(ss.str(), filters_[i].panel); \ 00454 } \ 00455 { \ 00456 std::stringstream ss; \ 00457 ss << " sizer " << i; \ 00458 printStuff(ss.str(), filters_[i].sizer); \ 00459 } \ 00460 } 00461 00462 void RosoutPanel::onProcessTimer(wxTimerEvent& evt) 00463 { 00464 callback_queue_.callAvailable(ros::WallDuration()); 00465 00466 processMessages(); 00467 00468 refilter_timer_ += 0.25f; 00469 if (needs_refilter_ && refilter_timer_ > 0.5f) 00470 { 00471 refilter_timer_ = 0.0f; 00472 needs_refilter_ = false; 00473 refilter(); 00474 } 00475 00476 //PRINT_STUFF("onProcessTimer"); 00477 } 00478 00479 RosoutTextFilterPtr RosoutPanel::createTextFilter() 00480 { 00481 RosoutTextFilterPtr filter(new RosoutTextFilter); 00482 RosoutTextFilterControl* control = new RosoutTextFilterControl(filters_window_, filter); 00483 addFilter(filter, control); 00484 00485 return filter; 00486 } 00487 00488 void RosoutPanel::onAddFilterPressed(wxCommandEvent& event) 00489 { 00490 createTextFilter(); 00491 } 00492 00493 void RosoutPanel::onClear(wxCommandEvent& event) 00494 { 00495 clear(); 00496 } 00497 00498 void RosoutPanel::addMessageToTable(const rosgraph_msgs::Log::ConstPtr& message, uint32_t id) 00499 { 00500 ordered_messages_.push_back(id); 00501 } 00502 00503 rosgraph_msgs::LogConstPtr RosoutPanel::getMessageByIndex(uint32_t index) const 00504 { 00505 if (index >= ordered_messages_.size()) 00506 { 00507 return rosgraph_msgs::LogConstPtr(); 00508 } 00509 00510 M_IdToMessage::const_iterator it = messages_.find(ordered_messages_[index]); 00511 ROS_ASSERT(it != messages_.end()); 00512 00513 return it->second; 00514 } 00515 00516 bool RosoutPanel::filter(uint32_t id) const 00517 { 00518 // No filters, always include 00519 if (filters_.empty()) 00520 { 00521 return true; 00522 } 00523 00524 M_IdToMessage::const_iterator it = messages_.find(id); 00525 ROS_ASSERT(it != messages_.end()); 00526 00527 const rosgraph_msgs::LogConstPtr& message = it->second; 00528 00529 // First run through the severity filter 00530 if (!severity_filter_->filter(message)) 00531 { 00532 return false; 00533 } 00534 00535 { 00536 V_FilterInfo::const_iterator it = filters_.begin(); 00537 V_FilterInfo::const_iterator end = filters_.end(); 00538 for (; it != end; ++it) 00539 { 00540 const FilterInfo& info = *it; 00541 const RosoutFilterPtr& filter = info.filter; 00542 if (filter->isEnabled() && filter->isValid()) 00543 { 00544 if (!filter->filter(message)) 00545 { 00546 return false; 00547 } 00548 } 00549 } 00550 } 00551 00552 return true; 00553 } 00554 00555 void RosoutPanel::validateOrderedMessages() 00556 { 00557 #if VALIDATE_FILTERING 00558 typedef std::set<uint32_t> S_u32; 00559 S_u32 s; 00560 V_u32::iterator it = ordered_messages_.begin(); 00561 V_u32::iterator end = ordered_messages_.end(); 00562 for (; it != end; ++it) 00563 { 00564 uint32_t id = *it; 00565 if (!s.insert(id).second) 00566 { 00567 ROS_BREAK(); 00568 } 00569 } 00570 #endif 00571 } 00572 00573 void RosoutPanel::refilter() 00574 { 00575 table_->preItemChanges(); 00576 00577 ordered_messages_.clear(); 00578 M_IdToMessage::iterator it = messages_.begin(); 00579 M_IdToMessage::iterator end = messages_.end(); 00580 for (; it != end; ++it) 00581 { 00582 uint32_t id = it->first; 00583 rosgraph_msgs::Log::ConstPtr& message = it->second; 00584 00585 if (filter(id)) 00586 { 00587 addMessageToTable(message, id); 00588 } 00589 } 00590 00591 validateOrderedMessages(); 00592 00593 table_->SetItemCount(ordered_messages_.size()); 00594 00595 table_->postItemChanges(); 00596 } 00597 00598 void RosoutPanel::popMessage() 00599 { 00600 M_IdToMessage::iterator it = messages_.begin(); 00601 if (!ordered_messages_.empty() && ordered_messages_.front() == it->first) 00602 { 00603 00604 ordered_messages_.erase(ordered_messages_.begin()); 00605 table_->SetItemCount(ordered_messages_.size()); 00606 00607 // Removing early messages means subtracting 1 from the current selection 00608 const S_int32& selection = table_->getSelection(); 00609 S_int32 new_selection; 00610 00611 S_int32::const_iterator it = selection.begin(); 00612 S_int32::const_iterator end = selection.end(); 00613 for (; it != end; ++it) 00614 { 00615 int32_t new_index = *it - 1; 00616 if (new_index >= 0) 00617 { 00618 new_selection.insert(new_index); 00619 } 00620 } 00621 00622 table_->setSelection(new_selection); 00623 } 00624 00625 messages_.erase(it); 00626 } 00627 00628 void RosoutPanel::processMessage(const rosgraph_msgs::Log::ConstPtr& message) 00629 { 00630 uint32_t id = message_id_counter_++; 00631 00632 messages_.insert(std::make_pair(id, message)); 00633 00634 if (filter(id)) 00635 { 00636 addMessageToTable(message, id); 00637 } 00638 00639 validateOrderedMessages(); 00640 00641 if (messages_.size() > max_messages_) 00642 { 00643 popMessage(); 00644 } 00645 } 00646 00647 void RosoutPanel::processMessages() 00648 { 00649 if (message_queue_.empty()) 00650 { 00651 return; 00652 } 00653 00654 table_->preItemChanges(); 00655 00656 V_Log::iterator it = message_queue_.begin(); 00657 V_Log::iterator end = message_queue_.end(); 00658 for (; it != end; ++it) 00659 { 00660 rosgraph_msgs::Log::ConstPtr& message = *it; 00661 00662 processMessage(message); 00663 } 00664 00665 message_queue_.clear(); 00666 00667 table_->SetItemCount(ordered_messages_.size()); 00668 00669 table_->postItemChanges(); 00670 } 00671 00672 void RosoutPanel::incomingMessage(const rosgraph_msgs::Log::ConstPtr& msg) 00673 { 00674 if (!pause_) 00675 { 00676 message_queue_.push_back(msg); 00677 } 00678 } 00679 00680 void RosoutPanel::onPause(wxCommandEvent& evt) 00681 { 00682 pause_ = evt.IsChecked(); 00683 } 00684 00685 void RosoutPanel::onSetup(wxCommandEvent& evt) 00686 { 00687 RosoutSetupDialog dialog(this, topic_, max_messages_); 00688 00689 if (dialog.ShowModal() == wxOK) 00690 { 00691 setTopic(dialog.getTopic()); 00692 setBufferSize(dialog.getBufferSize()); 00693 } 00694 } 00695 00696 void RosoutPanel::setBufferSize(uint32_t size) 00697 { 00698 max_messages_ = size; 00699 while (messages_.size() >= max_messages_) 00700 { 00701 popMessage(); 00702 } 00703 } 00704 00705 RosoutMessageSummary RosoutPanel::getMessageSummary(double duration) const 00706 { 00707 RosoutMessageSummary summary; 00708 ros::Time search_end(0); 00709 00710 if (ros::Time::now().toSec() - duration > 0) 00711 { 00712 search_end = ros::Time::now() - ros::Duration(duration); 00713 } 00714 00715 M_IdToMessage::const_reverse_iterator it = messages_.rbegin(); 00716 M_IdToMessage::const_reverse_iterator end = messages_.rend(); 00717 for (; it != end; ++it) 00718 { 00719 const rosgraph_msgs::Log::ConstPtr& msg = it->second; 00720 00721 if (msg->header.stamp < search_end) 00722 { 00723 break; 00724 } 00725 00726 switch (msg->level) 00727 { 00728 case rosgraph_msgs::Log::DEBUG: 00729 ++summary.debug; 00730 break; 00731 case rosgraph_msgs::Log::INFO: 00732 ++summary.info; 00733 break; 00734 case rosgraph_msgs::Log::WARN: 00735 ++summary.warn; 00736 break; 00737 case rosgraph_msgs::Log::ERROR: 00738 ++summary.error; 00739 break; 00740 case rosgraph_msgs::Log::FATAL: 00741 ++summary.fatal; 00742 break; 00743 } 00744 } 00745 00746 return summary; 00747 } 00748 00749 } // namespace rxtools