void ImageView::initPlugin(qt_gui_cpp::PluginContext& context) { widget_ = new QWidget(); ui_.setupUi(widget_); if (context.serialNumber() > 1) { widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")"); } context.addWidget(widget_); ros::NodeHandle nh; topic = nh.resolveName("image"); connect(ui_.image_topic, SIGNAL(textChanged(QString)), this, SLOT(onTextChanged(QString))); ui_.image_topic->setText(QString::fromStdString(topic)); }
void rov_status::initPlugin(qt_gui_cpp::PluginContext& context) { widget_ = new QWidget(); ui_.setupUi(widget_); if (context.serialNumber() > 1) { widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")"); } context.addWidget(widget_); this->subscriber_ = getNodeHandle().subscribe<videoray::Status>("videoray_status", 1, &rov_status::callback_status, this); ui_.firmware_label->setText("not set"); }
void Autopilot::initPlugin(qt_gui_cpp::PluginContext& context) { widget_ = new QWidget(); ui_.setupUi(widget_); if (context.serialNumber() > 1) { widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")"); } context.addWidget(widget_); // Enable / disable Heading/Depth checkboxes connect(ui_.desired_heading_checkbox, SIGNAL(toggled(bool)), this, SLOT(onEnableDesiredHeading(bool))); connect(ui_.desired_depth_checkbox, SIGNAL(toggled(bool)), this, SLOT(onEnableDesiredDepth(bool))); // Connect change of value in double spin box to function call connect(ui_.set_heading_button, SIGNAL(clicked(bool)), this, SLOT(onSetHeading(bool))); connect(ui_.set_depth_button, SIGNAL(clicked(bool)), this, SLOT(onSetDepth(bool))); // Create publisher this->desired_pub_ = getNodeHandle().advertise<videoray::DesiredTrajectory>("desired_trajectory", 1000); }
void SkirosGui::initPlugin(qt_gui_cpp::PluginContext& context) { ///Basic initializations nh_ptr_.reset(new ros::NodeHandle("")); widget_ = new QWidget(); ui_.setupUi(widget_); wm_ptr_.reset(new skiros_wm::WorldModelInterface(*nh_ptr_, true)); if(!wm_ptr_->isConnected()) FWARN("[SkirosGui::initPlugin] World model seems down, waiting..."); if(!wm_ptr_->waitConnection(ros::Duration(3.0)) && ros::ok()) { FWARN("[SkirosGui::initPlugin] World model seems down, waiting..."); } if(!ros::ok()) return; FINFO("[SkirosGui::initPlugin] Connected to world model"); ros::Duration(0.5).sleep();//Wait half second to avoid a weird bug where I don't detect the presence of robots skill_interface_ptr.reset(new skiros_skill::SkillLayerInterface()); if (context.serialNumber() > 1) { widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")"); } context.addWidget(widget_); ///Task manager interfaces task_exe_pub_ = nh_ptr_->advertise<skiros_msgs::TmTaskExe>(std::string(task_mgr_node_name) + task_exe_tpc_name, 10); task_monitor_sub_ = nh_ptr_->subscribe(std::string(task_mgr_node_name) + task_monitor_tpc_name, 5, &SkirosGui::tmFeedbackReceived, this); task_modify_ = nh_ptr_->serviceClient<skiros_msgs::TmModifyTask>(std::string(task_mgr_node_name) + task_modify_srv_name); task_query_ = nh_ptr_->serviceClient<skiros_msgs::TmQueryTask>(std::string(task_mgr_node_name) + task_query_srv_name); ///General timer = new QTimer(this); connect(timer, SIGNAL(timeout()), this, SLOT(refreshTimerCb())); timer->start(200); ui_.robot_combo_box->setCurrentIndex(ui_.robot_combo_box->findText("")); connect(ui_.robot_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(robotIndexChanged(int))); connect(ui_.modality_checkBox, SIGNAL(toggled(bool)), this, SLOT(modalityButtonClicked())); connect(ui_.exe_task_button, SIGNAL(pressed()), this, SLOT(exeTaskButtonClicked())); connect(ui_.stop_task_button, SIGNAL(pressed()), this, SLOT(stopTaskButtonClicked())); connect(this, SIGNAL(robotFeedbackReceived(const skiros_msgs::ModuleStatus &)), this, SLOT(robotMonitorCb(const skiros_msgs::ModuleStatus &))); connect(this, SIGNAL(tmFeedbackReceived(const skiros_msgs::TmMonitor &)), this, SLOT(taskMonitorCb(const skiros_msgs::TmMonitor &))); ///Goal tab ui_.goal_table_view->setModel(&goal_model_); task_plan_ = nh_ptr_->serviceClient<skiros_msgs::TmGoal>(std::string(task_mgr_node_name) + task_plan_srv_name); connect(ui_.condition_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(conditionIndexChanged(int))); connect(ui_.condition_refresh_button, SIGNAL(pressed()), this, SLOT(refreshButtonClicked())); connect(ui_.condition_add_button, SIGNAL(pressed()), this, SLOT(addConditionButtonClicked())); connect(ui_.condition_remove_button, SIGNAL(pressed()), this, SLOT(removeConditionButtonClicked())); connect(ui_.plan_button, SIGNAL(pressed()), this, SLOT(taskPlanButtonClicked())); ///Task tab ui_.skills_table_view->setModel(&skill_model_); ui_.skill_combo_box->setCurrentIndex(ui_.skill_combo_box->findText("")); connect(ui_.skill_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(skillIndexChanged(int))); //ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh")); connect(ui_.add_skill_button, SIGNAL(pressed()), this, SLOT(addSkillButtonClicked())); connect(ui_.remove_skill_button, SIGNAL(pressed()), this, SLOT(removeSkillButtonClicked())); updateTask(); ///Modules tab ui_.module_combo_box->setCurrentIndex(ui_.module_combo_box->findText("")); connect(ui_.module_combo_box, SIGNAL(currentIndexChanged(int)), this, SLOT(moduleIndexChanged(int))); //ui_.refresh_topics_push_button->setIcon(QIcon::fromTheme("view-refresh")); connect(ui_.exe_module_button, SIGNAL(pressed()), this, SLOT(exeModuleButtonClicked())); connect(ui_.stop_module_button, SIGNAL(pressed()), this, SLOT(stopModuleButtonClicked())); ///World model tab wm_model_ptr_ = new TreeModel(wm_ptr_->getElement(0)); ui_.world_model_tree_view->setModel(wm_model_ptr_); ui_.world_model_tree_view->setModel(wm_model_ptr_); connect(ui_.world_model_tree_view->selectionModel(), SIGNAL(currentChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(onWmTreeSelectionChanged(const QModelIndex &, const QModelIndex &))); connect(ui_.remove_object_button, SIGNAL(pressed()), this, SLOT(removeWmElementButtonClicked())); connect(ui_.add_object_button, SIGNAL(pressed()), this, SLOT(addWmElementButtonClicked())); connect(ui_.modify_object_button, SIGNAL(pressed()), this, SLOT(modifyWmElementButtonClicked())); connect(ui_.saveScene_button, SIGNAL(pressed()), this, SLOT(saveSceneButtonClicked())); connect(ui_.loadScene_button, SIGNAL(pressed()), this, SLOT(loadSceneButtonClicked())); scene_load_save_ = nh_ptr_->serviceClient<skiros_msgs::WmSceneLoadAndSave>(std::string(world_model_node_name) + wm_scene_load_save_srv_name); interactive_m_server_.reset( new interactive_markers::InteractiveMarkerServer("skiros_obj_edit") ); ///Logging tab connect(ui_.startstoplog_button, SIGNAL(pressed()), this, SLOT(startLogButtonClicked())); connect(ui_.logFile_lineEdit, SIGNAL(returnPressed()), this, SLOT(logFileChanged())); }