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
00030 #include "rosout_list_control.h"
00031 #include "rosout_generated.h"
00032 #include "rosout_panel.h"
00033 #include "rosout_text_filter.h"
00034
00035 #include <ros/assert.h>
00036
00037 #include <boost/algorithm/string/join.hpp>
00038 #include <boost/regex.hpp>
00039
00040 #include <wx/imaglist.h>
00041 #include <wx/artprov.h>
00042 #include <wx/clipbrd.h>
00043
00044 #include <sstream>
00045
00046 namespace rxtools
00047 {
00048
00049 RosoutListControl::RosoutListControl(wxWindow* parent, wxWindowID id, const wxPoint& pos, const wxSize& size, long style, const wxValidator& validator,
00050 const wxString& name)
00051 : wxListCtrl(parent, id, pos, size, style, validator, name)
00052 , last_selection_(-1)
00053 , scrollbar_at_bottom_(true)
00054 , disable_scroll_to_bottom_(false)
00055 #if __WXMAC__
00056 , manual_selection_(false)
00057 #endif
00058 {
00059 wxListItem item;
00060 item.SetText(wxT("Message"));
00061 item.SetWidth(600);
00062 InsertColumn(columns::Message, item);
00063 item.SetText(wxT("Severity"));
00064 item.SetWidth(100);
00065 InsertColumn(columns::Severity, item);
00066 item.SetText(wxT("Node"));
00067 item.SetWidth(200);
00068 InsertColumn(columns::Node, item);
00069 item.SetText(wxT("Time"));
00070 item.SetWidth(200);
00071 InsertColumn(columns::Time, item);
00072 item.SetText(wxT("Topics"));
00073 item.SetWidth(200);
00074 InsertColumn(columns::Topics, item);
00075 item.SetText(wxT("Location"));
00076 item.SetWidth(600);
00077 InsertColumn(columns::Location, item);
00078
00079
00080 wxImageList* image_list = new wxImageList(16, 16);
00081 fatal_image_id_ = image_list->Add(wxArtProvider::GetIcon(wxART_CROSS_MARK, wxART_OTHER, wxSize(16, 16)));
00082 error_image_id_ = image_list->Add(wxArtProvider::GetIcon(wxART_ERROR, wxART_OTHER, wxSize(16, 16)));
00083 warning_image_id_ = image_list->Add(wxArtProvider::GetIcon(wxART_WARNING, wxART_OTHER, wxSize(16, 16)));
00084 info_image_id_ = image_list->Add(wxArtProvider::GetIcon(wxART_INFORMATION, wxART_OTHER, wxSize(16, 16)));
00085 debug_image_id_ = image_list->Add(wxArtProvider::GetIcon(wxART_HELP, wxART_OTHER, wxSize(16, 16)));
00086
00087 AssignImageList(image_list, wxIMAGE_LIST_SMALL);
00088
00089 Connect(wxEVT_COMMAND_LIST_ITEM_ACTIVATED, wxListEventHandler(RosoutListControl::onItemActivated), NULL, this);
00090 Connect(wxEVT_COMMAND_LIST_ITEM_RIGHT_CLICK, wxListEventHandler(RosoutListControl::onItemRightClick), NULL, this);
00091 Connect(wxEVT_COMMAND_LIST_ITEM_SELECTED, wxListEventHandler(RosoutListControl::onItemSelected), NULL, this);
00092 Connect(wxEVT_CHAR, wxKeyEventHandler(RosoutListControl::onChar));
00093
00094 }
00095
00096 RosoutListControl::~RosoutListControl()
00097 {
00098 }
00099
00100 void RosoutListControl::setModel(RosoutPanel* model)
00101 {
00102 model_ = model;
00103 }
00104
00105 wxString RosoutListControl::getSeverityText(const rosgraph_msgs::LogConstPtr& message) const
00106 {
00107 switch (message->level)
00108 {
00109 case rosgraph_msgs::Log::DEBUG:
00110 return wxT("Debug");
00111 case rosgraph_msgs::Log::INFO:
00112 return wxT("Info");
00113 case rosgraph_msgs::Log::WARN:
00114 return wxT("Warn");
00115 case rosgraph_msgs::Log::ERROR:
00116 return wxT("Error");
00117 case rosgraph_msgs::Log::FATAL:
00118 return wxT("Fatal");
00119 }
00120
00121 return wxT("Unknown");
00122 }
00123
00124 int RosoutListControl::OnGetItemImage(long item) const
00125 {
00126 ROS_ASSERT(model_);
00127
00128 rosgraph_msgs::LogConstPtr message = model_->getMessageByIndex(item);
00129 if (!message)
00130 {
00131 return -1;
00132 }
00133
00134 switch (message->level)
00135 {
00136 case rosgraph_msgs::Log::DEBUG:
00137 return debug_image_id_;
00138 case rosgraph_msgs::Log::INFO:
00139 return info_image_id_;
00140 case rosgraph_msgs::Log::WARN:
00141 return warning_image_id_;
00142 case rosgraph_msgs::Log::ERROR:
00143 return error_image_id_;
00144 case rosgraph_msgs::Log::FATAL:
00145 return fatal_image_id_;
00146 }
00147
00148 return -1;
00149 }
00150
00151 wxListItemAttr * RosoutListControl::OnGetItemAttr(long item) const
00152 {
00153 #if 0
00154 ROS_ASSERT(model_);
00155
00156 const rosgraph_msgs::Log& message = model_->getMessageByIndex(item);
00157
00158 switch( message->level )
00159 {
00160 case rosgraph_msgs::Log::DEBUG:
00161 attr_.SetBackgroundColour( wxColour( 204, 255, 204 ) );
00162 break;
00163 case rosgraph_msgs::Log::INFO:
00164 attr_.SetBackgroundColour( *wxWHITE );
00165 break;
00166 case rosgraph_msgs::Log::WARN:
00167 attr_.SetBackgroundColour( wxColour( 255, 255, 153 ) );
00168 break;
00169 case rosgraph_msgs::Log::ERROR:
00170 attr_.SetBackgroundColour( wxColour( 255, 153, 0 ) );
00171 break;
00172 case rosgraph_msgs::Log::FATAL:
00173 attr_.SetBackgroundColour( *wxRED );
00174 break;
00175 default:
00176 ROS_BREAK();
00177 }
00178 #endif
00179
00180 return &attr_;
00181 }
00182
00183 wxString RosoutListControl::OnGetItemText(long item, long column) const
00184 {
00185 ROS_ASSERT(model_);
00186
00187 rosgraph_msgs::LogConstPtr message = model_->getMessageByIndex(item);
00188 if (!message)
00189 {
00190 return wxString();
00191 }
00192
00193 switch (column)
00194 {
00195 case columns::Severity:
00196 {
00197 return getSeverityText(message);
00198 }
00199 break;
00200 case columns::Time:
00201 {
00202 std::stringstream ss;
00203 ss << message->header.stamp;
00204 return wxString::FromAscii(ss.str().c_str());
00205 }
00206 case columns::Message:
00207 {
00208 std::string msg = message->msg;
00209 size_t pos = std::string::npos;
00210 while (true)
00211 {
00212 pos = msg.find('\n');
00213 if (pos == std::string::npos)
00214 {
00215 break;
00216 }
00217
00218 msg.replace(pos, 1, "\\n");
00219 }
00220 while (true)
00221 {
00222 pos = msg.find('\r');
00223 if (pos == std::string::npos)
00224 {
00225 break;
00226 }
00227
00228 msg.replace(pos, 1, "\\r");
00229 }
00230 return wxString::FromAscii(msg.c_str());
00231 }
00232 case columns::Topics:
00233 {
00234 std::stringstream ss;
00235 typedef std::vector<std::string> V_string;
00236 V_string::const_iterator it = message->topics.begin();
00237 V_string::const_iterator end = message->topics.end();
00238 for (; it != end; ++it)
00239 {
00240 if (it != message->topics.begin())
00241 {
00242 ss << ", ";
00243 }
00244
00245 ss << *it;
00246 }
00247
00248 return wxString::FromAscii(ss.str().c_str());
00249 }
00250 case columns::Location:
00251 {
00252 wxString str;
00253 str << wxString::FromAscii(message->file.c_str()) << wxT(":") << wxString::FromAscii(message->function.c_str()) << wxT(":") << message->line;
00254 return str;
00255 }
00256 case columns::Node:
00257 {
00258 return wxString::FromAscii(message->name.c_str());
00259 }
00260 }
00261
00262 ROS_BREAK();
00263 return wxT("Unknown Column");
00264 }
00265
00266 void TextboxDialog::onChar(wxKeyEvent& event)
00267 {
00268 int key = event.GetKeyCode();
00269 if (key == WXK_ESCAPE)
00270 {
00271 wxObject* obj = event.GetEventObject();
00272 wxWindow* win = wxDynamicCast(obj, wxWindow);
00273 if (win)
00274 {
00275 if (win->GetParent())
00276 {
00277 win->GetParent()->Close();
00278 }
00279 else
00280 {
00281 win->Close();
00282 }
00283 }
00284 }
00285
00286 else if (key == 3)
00287 {
00288 wxObject* obj = event.GetEventObject();
00289 wxRichTextCtrl* text = wxDynamicCast(obj, wxRichTextCtrl);
00290 if (text)
00291 {
00292 text->Copy();
00293 }
00294
00295 event.Skip();
00296 }
00297 else
00298 {
00299 event.Skip();
00300 }
00301 }
00302
00303 void RosoutListControl::onItemActivated(wxListEvent& event)
00304 {
00305 ROS_ASSERT(model_);
00306
00307 rosgraph_msgs::LogConstPtr message = model_->getMessageByIndex(event.GetIndex());
00308 if (!message)
00309 {
00310 return;
00311 }
00312
00313 TextboxDialog* dialog = new TextboxDialog(this, wxID_ANY);
00314 dialog->Show();
00315 dialog->text_->SetFocus();
00316
00317 wxRichTextCtrl& t = *dialog->text_;
00318
00319
00320 {
00321 t.BeginBold();
00322 t.WriteText(wxT("Node: "));
00323 t.EndBold();
00324 t.WriteText(wxString::FromAscii(message->name.c_str()));
00325 t.Newline();
00326 }
00327
00328
00329 {
00330 t.BeginBold();
00331 t.WriteText(wxT("Time: "));
00332 t.EndBold();
00333 std::stringstream ss;
00334 ss << message->header.stamp;
00335 t.WriteText(wxString::FromAscii(ss.str().c_str()));
00336 t.Newline();
00337 }
00338
00339
00340 {
00341 t.BeginBold();
00342 t.WriteText(wxT("Severity: "));
00343 t.EndBold();
00344 t.WriteText(getSeverityText(message));
00345 t.Newline();
00346 }
00347
00348
00349 {
00350 if (!message->file.empty())
00351 {
00352 t.BeginBold();
00353 t.WriteText(wxT("Location: "));
00354 t.EndBold();
00355 std::stringstream ss;
00356 ss << message->file << ":" << message->function << ":" << message->line;
00357 t.WriteText(wxString::FromAscii(ss.str().c_str()));
00358 t.Newline();
00359 }
00360 }
00361
00362
00363 {
00364 t.BeginBold();
00365 t.WriteText(wxT("Published Topics: "));
00366 t.EndBold();
00367 t.WriteText(wxString::FromAscii(boost::join(message->topics, ", ").c_str()));
00368 t.Newline();
00369 }
00370
00371
00372 {
00373 t.Newline();
00374 t.BeginTextColour(wxColour(127, 61, 2));
00375 t.BeginBold();
00376 t.WriteText(wxString::FromAscii(message->msg.c_str()));
00377 t.EndTextColour();
00378 t.EndBold();
00379 }
00380 }
00381
00382 std::string escapeForRegex(const std::string& str)
00383 {
00384 const static boost::regex esc("[\\^\\.\\$\\|\\(\\)\\[\\]\\*\\+\\?\\/\\\\]");
00385 const static std::string rep("\\\\\\1&");
00386 return boost::regex_replace(str, esc, rep, boost::match_default | boost::format_sed);
00387 }
00388
00389 void addFilter(RosoutPanel* model, const std::string& text, uint32_t field_mask, bool include, bool new_window)
00390 {
00391 if (new_window)
00392 {
00393 RosoutFrame* frame = model->createNewFrame();
00394 model = frame->rosout_panel_;
00395 model->clearFilters();
00396 }
00397
00398 RosoutTextFilterPtr filter = model->createTextFilter();
00399 filter->setFilterType(include ? RosoutTextFilter::Include : RosoutTextFilter::Exclude);
00400 filter->setFieldMask(field_mask);
00401 filter->setText("^" + escapeForRegex(text) + "$");
00402 filter->setUseRegex(true);
00403 model->refilter();
00404 }
00405
00406 rosgraph_msgs::LogConstPtr RosoutListControl::getSelectedMessage()
00407 {
00408 if (last_selection_ == -1)
00409 {
00410 return rosgraph_msgs::LogConstPtr();
00411 }
00412
00413 return model_->getMessageByIndex(last_selection_);
00414 }
00415
00416 void RosoutListControl::onExcludeLocation(wxCommandEvent& event)
00417 {
00418 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00419 {
00420 std::stringstream ss;
00421 ss << message->file << ":" << message->function << ":" << message->line;
00422 addFilter(model_, ss.str(), RosoutTextFilter::Location, false, false);
00423 }
00424 }
00425
00426 void RosoutListControl::onExcludeNode(wxCommandEvent& event)
00427 {
00428 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00429 {
00430 addFilter(model_, message->name, RosoutTextFilter::Node, false, false);
00431 }
00432 }
00433
00434 void RosoutListControl::onExcludeMessage(wxCommandEvent& event)
00435 {
00436 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00437 {
00438 addFilter(model_, message->msg, RosoutTextFilter::Message, false, false);
00439 }
00440 }
00441
00442 void RosoutListControl::onExcludeLocationNewWindow(wxCommandEvent& event)
00443 {
00444 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00445 {
00446 std::stringstream ss;
00447 ss << message->file << ":" << message->function << ":" << message->line;
00448 addFilter(model_, ss.str(), RosoutTextFilter::Location, false, true);
00449 }
00450 }
00451
00452 void RosoutListControl::onExcludeNodeNewWindow(wxCommandEvent& event)
00453 {
00454 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00455 {
00456 addFilter(model_, message->name, RosoutTextFilter::Node, false, true);
00457 }
00458 }
00459
00460 void RosoutListControl::onExcludeMessageNewWindow(wxCommandEvent& event)
00461 {
00462 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00463 {
00464 addFilter(model_, message->msg, RosoutTextFilter::Message, false, true);
00465 }
00466 }
00467
00468 void RosoutListControl::onIncludeLocation(wxCommandEvent& event)
00469 {
00470 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00471 {
00472 std::stringstream ss;
00473 ss << message->file << ":" << message->function << ":" << message->line;
00474 addFilter(model_, ss.str(), RosoutTextFilter::Location, true, false);
00475 }
00476 }
00477
00478 void RosoutListControl::onIncludeNode(wxCommandEvent& event)
00479 {
00480 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00481 {
00482 addFilter(model_, message->name, RosoutTextFilter::Node, true, false);
00483 }
00484 }
00485
00486 void RosoutListControl::onIncludeMessage(wxCommandEvent& event)
00487 {
00488 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00489 {
00490 addFilter(model_, message->msg, RosoutTextFilter::Message, true, false);
00491 }
00492 }
00493
00494 void RosoutListControl::onIncludeLocationNewWindow(wxCommandEvent& event)
00495 {
00496 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00497 {
00498 std::stringstream ss;
00499 ss << message->file << ":" << message->function << ":" << message->line;
00500 addFilter(model_, ss.str(), RosoutTextFilter::Location, true, true);
00501 }
00502 }
00503
00504 void RosoutListControl::onIncludeNodeNewWindow(wxCommandEvent& event)
00505 {
00506 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00507 {
00508 addFilter(model_, message->name, RosoutTextFilter::Node, true, true);
00509 }
00510 }
00511
00512 void RosoutListControl::onIncludeMessageNewWindow(wxCommandEvent& event)
00513 {
00514 if (rosgraph_msgs::LogConstPtr message = getSelectedMessage())
00515 {
00516 addFilter(model_, message->msg, RosoutTextFilter::Message, true, true);
00517 }
00518 }
00519
00520 void RosoutListControl::copySelectionToClipboard(bool message_only)
00521 {
00522 updateSelection();
00523
00524 std::stringstream ss;
00525 S_int32::const_iterator it = selection_.begin();
00526 S_int32::const_iterator end = selection_.end();
00527 for (; it != end; ++it)
00528 {
00529 int32_t index = *it;
00530
00531 if (it != selection_.begin())
00532 {
00533 ss << std::endl << std::endl;
00534 }
00535
00536 rosgraph_msgs::LogConstPtr message = model_->getMessageByIndex(index);
00537 if (message)
00538 {
00539 if (message_only)
00540 {
00541 ss << message->msg;
00542 }
00543 else
00544 {
00545 ss << *message;
00546 }
00547 }
00548 }
00549
00550 if (wxTheClipboard->Open())
00551 {
00552 wxTheClipboard->SetData(new wxTextDataObject(wxString::FromAscii(ss.str().c_str())));
00553 wxTheClipboard->Close();
00554 }
00555 }
00556
00557 void RosoutListControl::onCopy(wxCommandEvent& event)
00558 {
00559 copySelectionToClipboard(false);
00560 }
00561
00562 void RosoutListControl::onCopyMessageOnly(wxCommandEvent& event)
00563 {
00564 copySelectionToClipboard(true);
00565 }
00566
00567 void RosoutListControl::onChar(wxKeyEvent& event)
00568 {
00569 int key = event.GetKeyCode();
00570
00571 if (key == 3)
00572 {
00573 copySelectionToClipboard(false);
00574 event.Skip();
00575 }
00576 }
00577
00578 void RosoutListControl::onItemRightClick(wxListEvent& event)
00579 {
00580 updateSelection();
00581 ROS_ASSERT(model_);
00582
00583 wxMenu* menu = new wxMenu(wxT(""));
00584 wxMenuItem* item = 0;
00585
00586 item = menu->Append(wxID_COPY, wxT("&Copy\tCtrl+C"));
00587 Connect(wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onCopy));
00588 item = menu->Append(wxID_ANY, wxT("Copy &Message Only"));
00589 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onCopyMessageOnly), NULL, this);
00590
00591
00592 if (selection_.size() == 1)
00593 {
00594 rosgraph_msgs::LogConstPtr message = model_->getMessageByIndex(event.GetIndex());
00595 if (message)
00596 {
00597 wxMenu* exclude_menu = new wxMenu(wxT(""));
00598 wxMenu* include_menu = new wxMenu(wxT(""));
00599
00600
00601 {
00602 if (!message->file.empty())
00603 {
00604 item = include_menu->Append(wxID_ANY, wxT("This Location"));
00605 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeLocation), NULL, this);
00606 item = include_menu->Append(wxID_ANY, wxT("This Location (New Window)"));
00607 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeLocationNewWindow), NULL, this);
00608 }
00609
00610 item = include_menu->Append(wxID_ANY, wxT("This Node"));
00611 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeNode), NULL, this);
00612 item = include_menu->Append(wxID_ANY, wxT("This Node (New Window)"));
00613 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeNodeNewWindow), NULL, this);
00614 item = include_menu->Append(wxID_ANY, wxT("This Message"));
00615 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeMessage), NULL, this);
00616 item = include_menu->Append(wxID_ANY, wxT("This Message (New Window)"));
00617 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onIncludeMessageNewWindow), NULL, this);
00618
00619 menu->AppendSubMenu(include_menu, wxT("&Include"));
00620 }
00621
00622
00623 {
00624 if (!message->file.empty())
00625 {
00626 item = exclude_menu->Append(wxID_ANY, wxT("This Location"));
00627 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeLocation), NULL, this);
00628 item = exclude_menu->Append(wxID_ANY, wxT("This Location (New Window)"));
00629 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeLocationNewWindow), NULL, this);
00630 }
00631
00632 item = exclude_menu->Append(wxID_ANY, wxT("This Node"));
00633 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeNode), NULL, this);
00634 item = exclude_menu->Append(wxID_ANY, wxT("This Node (New Window)"));
00635 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeNodeNewWindow), NULL, this);
00636 item = exclude_menu->Append(wxID_ANY, wxT("This Message"));
00637 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeMessage), NULL, this);
00638 item = exclude_menu->Append(wxID_ANY, wxT("This Message (New Window)"));
00639 Connect(item->GetId(), wxEVT_COMMAND_MENU_SELECTED, wxCommandEventHandler(RosoutListControl::onExcludeMessageNewWindow), NULL, this);
00640
00641 menu->AppendSubMenu(exclude_menu, wxT("&Exclude"));
00642 }
00643 }
00644 }
00645
00646 PopupMenu(menu);
00647 }
00648
00649 void RosoutListControl::updateSelection()
00650 {
00651 selection_.clear();
00652
00653 int32_t index = -1;
00654 while (true)
00655 {
00656 index = GetNextItem(index, wxLIST_NEXT_ALL, wxLIST_STATE_SELECTED);
00657 if (index == -1)
00658 {
00659 break;
00660 }
00661
00662 selection_.insert(index);
00663 }
00664 }
00665
00666 void RosoutListControl::onItemSelected(wxListEvent& event)
00667 {
00668 last_selection_ = event.GetIndex();
00669
00670 updateSelection();
00671
00672 #if __WXMAC__
00673 if (!manual_selection_)
00674 {
00675 #endif
00676
00677 disable_scroll_to_bottom_ = true;
00678
00679 #if __WXMAC__
00680 }
00681 manual_selection_ = false;
00682 #endif
00683 }
00684
00685 void RosoutListControl::preItemChanges()
00686 {
00688 scrollbar_at_bottom_ = false;
00689 int count_per_page = GetCountPerPage();
00690 int scroll_pos = GetScrollPos(wxVERTICAL);
00691 #if __WXMAC__
00692
00693
00694 int32_t item_height = 20;
00695 if (GetItemCount() > 0)
00696 {
00697 wxRect rect;
00698 if (GetItemRect(0, rect))
00699 {
00700
00701 if (rect.GetHeight() > 0)
00702 {
00703 item_height = rect.GetHeight();
00704 }
00705 }
00706 }
00707
00708 scroll_pos /= item_height;
00709 #endif
00710 if (scroll_pos + count_per_page >= GetItemCount())
00711 {
00712 scrollbar_at_bottom_ = true;
00713 }
00714
00715 Freeze();
00716 }
00717
00718 void RosoutListControl::postItemChanges()
00719 {
00720 if (!disable_scroll_to_bottom_ && scrollbar_at_bottom_ && GetItemCount() > 0)
00721 {
00722 EnsureVisible(GetItemCount() - 1);
00723 }
00724
00725 disable_scroll_to_bottom_ = false;
00726
00727
00728 #if __WXMAC__
00729 setSelection(selection_);
00730 #endif
00731
00732 Thaw();
00733
00734
00735 #if wxMAJOR_VERSION == 2 and wxMINOR_VERSION == 8 // If wxWidgets 2.8.x
00736 wxIdleEvent idle;
00737 wxTheApp->SendIdleEvents(this, idle);
00738 #endif
00739 }
00740
00741 void RosoutListControl::setSelection(const S_int32& sel)
00742 {
00743 #if __WXMAC__
00744 manual_selection_ = true;
00745 #endif
00746
00747
00748 {
00749 S_int32::const_iterator it = sel.begin();
00750 S_int32::const_iterator end = sel.end();
00751 for (; it != end; ++it)
00752 {
00753 int32_t index = *it;
00754 ROS_ASSERT(index >= 0);
00755
00756 SetItemState(index, wxLIST_STATE_SELECTED, wxLIST_STATE_SELECTED);
00757 }
00758 }
00759
00760
00761 {
00762 S_int32::const_iterator it = selection_.begin();
00763 S_int32::const_iterator end = selection_.end();
00764 for (; it != end; ++it)
00765 {
00766 int32_t index = *it;
00767 ROS_ASSERT(index >= 0);
00768
00769 SetItemState(index, 0, wxLIST_STATE_SELECTED|wxLIST_STATE_FOCUSED);
00770 }
00771 }
00772
00773 selection_ = sel;
00774 }
00775
00776 }