///Connect Signals and Slots for the ui control void ui_connections(QObject* ui, GraphManager* graph_mgr, OpenNIListener* listener) { Qt::ConnectionType ctype = Qt::AutoConnection; if (ParameterServer::instance()->get<bool>("concurrent_io")) ctype = Qt::DirectConnection; QObject::connect(ui, SIGNAL(reset()), graph_mgr, SLOT(reset()), ctype); QObject::connect(ui, SIGNAL(optimizeGraph()), graph_mgr, SLOT(optimizeGraph()), ctype); QObject::connect(ui, SIGNAL(togglePause()), listener, SLOT(togglePause()), ctype); QObject::connect(ui, SIGNAL(toggleBagRecording()), listener, SLOT(toggleBagRecording()), ctype); QObject::connect(ui, SIGNAL(getOneFrame()), listener, SLOT(getOneFrame()), ctype); QObject::connect(ui, SIGNAL(deleteLastFrame()), graph_mgr, SLOT(deleteLastFrame()), ctype); QObject::connect(ui, SIGNAL(sendAllClouds()), graph_mgr, SLOT(sendAllClouds()), ctype); QObject::connect(ui, SIGNAL(saveAllClouds(QString)), graph_mgr, SLOT(saveAllClouds(QString)), ctype); QObject::connect(ui, SIGNAL(saveOctomapSig(QString)), graph_mgr, SLOT(saveOctomap(QString)), ctype); QObject::connect(ui, SIGNAL(saveAllFeatures(QString)), graph_mgr, SLOT(saveAllFeatures(QString)), ctype); QObject::connect(ui, SIGNAL(saveIndividualClouds(QString)), graph_mgr, SLOT(saveIndividualClouds(QString)), ctype); QObject::connect(ui, SIGNAL(saveTrajectory(QString)), graph_mgr, SLOT(saveTrajectory(QString)), ctype); QObject::connect(ui, SIGNAL(toggleMapping(bool)), graph_mgr, SLOT(toggleMapping(bool)), ctype); QObject::connect(ui, SIGNAL(saveG2OGraph(QString)), graph_mgr, SLOT(saveG2OGraph(QString)), ctype); }
void RosUi::bagRecording(bool _record_on) { if(this->record_on == _record_on){ return; } this->record_on = _record_on; Q_EMIT toggleBagRecording(); if(_record_on) { ROS_INFO("Recording Bagfile."); } else { ROS_INFO("Stopped Recording."); } }