Go to the documentation of this file.00001 #include "qnodedialog.h"
00002 #include "ui_qnodedialog.h"
00003 #include <boost/make_shared.hpp>
00004 #include <QSettings>
00005 #include <QMessageBox>
00006
00007 std::string getDefaultMasterURI()
00008 {
00009 if( qgetenv("ROS_MASTER_URI").isEmpty() )
00010 {
00011 QMessageBox msgBox;
00012 msgBox.setText("WARNINGS: the ROS_MASTER_URI is not defined in your environment\n"
00013 "Using the default value [http://localhost:11311]\n");
00014 msgBox.exec();
00015 return "http://localhost:11311";
00016 }
00017 else{
00018 auto master_uri = ( qgetenv("ROS_MASTER_URI"));
00019 return std::string( master_uri.data() );
00020 }
00021 }
00022
00023 QNodeDialog::QNodeDialog( QWidget *parent) :
00024 QDialog(parent),
00025 ui(new Ui::QNodeDialog)
00026 {
00027 ui->setupUi(this);
00028
00029 QSettings settings( "IcarusTechnology", "PlotJuggler");
00030
00031 auto master_ui = settings.value("QNode.master_uri", tr("http://localhost:11311")).toString();
00032 auto host_ip = settings.value("QNode.host_ip", tr("localhost")).toString();
00033
00034 ui->lineEditMaster->setText( master_ui );
00035 ui->lineEditHost->setText( host_ip );
00036 }
00037
00038 namespace ros {
00039 namespace master {
00040 void init(const M_string& remappings);
00041 }
00042 }
00043
00044 bool QNodeDialog::Connect(const std::string& ros_master_uri,
00045 const std::string& hostname)
00046 {
00047 std::map<std::string,std::string> remappings;
00048 remappings["__master"] = ros_master_uri;
00049 remappings["__hostname"] = hostname;
00050
00051 static bool first_time = true;
00052 if( first_time)
00053 {
00054 ros::init(remappings,"PlotJugglerListener");
00055 first_time = false;
00056 }
00057 else{
00058 ros::master::init(remappings);
00059 }
00060
00061 bool connected = ros::master::check();
00062 if ( ! connected ) {
00063 QMessageBox msgBox;
00064 msgBox.setText( QString("Could not connect to the ros master [%1]").
00065 arg(QString::fromStdString(ros_master_uri)));
00066 msgBox.exec();
00067 }
00068 return connected;
00069 }
00070
00071
00072 QNodeDialog::~QNodeDialog()
00073 {
00074 QSettings settings( "IcarusTechnology", "PlotJuggler");
00075 settings.setValue ("QNode.master_uri", ui->lineEditMaster->text() );
00076 settings.setValue("QNode.host_ip", ui->lineEditHost->text() );
00077 delete ui;
00078 }
00079
00080 void QNodeDialog::on_pushButtonConnect_pressed()
00081 {
00082 bool connected = false;
00083 if( ui->checkBoxUseEnvironment->isChecked() )
00084 {
00085 const std::string master_uri = getDefaultMasterURI();
00086 connected = QNodeDialog::Connect(master_uri, "localhost" );
00087 }
00088 else{
00089 std::string ros_master_uri = ui->lineEditMaster->text().toStdString();
00090 std::string hostname = ui->lineEditHost->text().toStdString();
00091 connected = QNodeDialog::Connect(ros_master_uri, hostname);
00092 }
00093 if( connected ) {
00094 this->close();
00095 }
00096 else{
00097
00098 }
00099 }
00100
00101
00102 void QNodeDialog::on_checkBoxUseEnvironment_toggled(bool checked)
00103 {
00104 ui->lineEditMaster->setEnabled( !checked );
00105 ui->lineEditHost->setEnabled( !checked );
00106 }
00107
00108
00109 void QNodeDialog::on_pushButtonCancel_pressed()
00110 {
00111 this->close();
00112 }
00113
00114 RosManager &RosManager::get()
00115 {
00116 static RosManager manager;
00117 return manager;
00118 }
00119
00120 void RosManager::stopROS()
00121 {
00122 if(ros::isStarted() )
00123 {
00124 ros::shutdown();
00125 ros::waitForShutdown();
00126 }
00127 }
00128
00129 RosManager::~RosManager()
00130 {
00131
00132 }
00133
00134 ros::NodeHandlePtr RosManager::getNode()
00135 {
00136 RosManager& manager = RosManager::get();
00137
00138 if(!ros::isInitialized() || !ros::master::check() )
00139 {
00140 bool connected = QNodeDialog::Connect(getDefaultMasterURI(), "localhost" );
00141 if ( ! connected )
00142 {
00143
00144 QNodeDialog dialog;
00145 dialog.exec();
00146 }
00147 }
00148 if ( ros::master::check() && ros::isInitialized())
00149 {
00150 if( !manager._node ){
00151 manager._node = ros::NodeHandlePtr(new ros::NodeHandle, [](ros::NodeHandle* node)
00152 {
00153 RosManager::get().stopROS();
00154 } );
00155 }
00156 ros::start();
00157 }
00158 return manager._node;
00159 }