void VisualizationManager::updateFrames() { typedef std::vector<std::string> V_string; V_string frames; frame_manager_->getTFClient()->getFrameStrings( frames ); // Check the fixed frame to see if it's ok std::string error; if( frame_manager_->frameHasProblems( getFixedFrame().toStdString(), ros::Time(), error )) { if( frames.empty() ) { // fixed_prop->setToWarn(); std::stringstream ss; ss << "No tf data. Actual error: " << error; global_status_->setStatus( StatusProperty::Warn, "Fixed Frame", QString::fromStdString( ss.str() )); } else { // fixed_prop->setToError(); global_status_->setStatus( StatusProperty::Error, "Fixed Frame", QString::fromStdString( error )); } } else { // fixed_prop->setToOK(); global_status_->setStatus( StatusProperty::Ok, "Fixed Frame", "OK" ); } }
void TopicDisplayDialog::onTreeItemActivated(wxTreeEvent& event) { V_string selection; topic_display_panel_->getSelectedTopics(selection); if (!selection.empty()) { EndModal(wxID_OK); } }
void TopicDisplayDialog::onOK(wxCommandEvent& event) { V_string selection; topic_display_panel_->getSelectedTopics(selection); if (!selection.empty()) { EndModal(wxID_OK); } else { wxMessageBox(wxT("Please select a topic!"), wxT("No topic selected"), wxOK | wxCENTRE | wxICON_ERROR, this); } }