mainwindow.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, CoroWare
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Stanford U. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "mainwindow.h"
00031 #include "ui_mainwindow.h"
00032 
00033 #ifdef Q_WS_WIN
00034 #include "windows.h"
00035 #include "mmsystem.h"
00036 #endif
00037 
00038 
00039 MainWindow::MainWindow(QWidget *parent) :
00040     QMainWindow(parent),
00041     ui(new Ui::MainWindow)
00042 {
00043     //set the parent widgets to the different widget created
00044     r.setParent(this);
00045     ui->setupUi(this);
00046     arm.setParent(ui->frame);
00047     arm_rotation.setParent(ui->frame_6);
00048     gripper.setParent(ui->frame_7);
00049     wrist.setParent(ui->frame_8);
00050     gps.setParent(ui->webView);
00051     gps.setList(ui->listWidget);
00052     hokuyo.setParent(ui->frame_hokuyo);
00053     gpsUrlTImer.invalidate();
00054 
00055     ui->tabWidget_5->setFocus();
00056 
00057     LRF_lines_show = false;
00058     IR_data_show = false;
00059 
00060 
00061     //connect signals to slots.
00062 
00063     connect(ui->connect,SIGNAL(clicked()),this,SLOT(connect_clicked()));//connect button pushed
00064 
00065 
00066     //***************************************************************************
00067     // Arm
00068     connect(&arm,SIGNAL(shoulderAngle_rad(double)),&r,SLOT(moveShoulderArm(double)));
00069     connect(&arm_rotation,SIGNAL(armAngle_rad(double)),&r,SLOT(rotateArm(double)));
00070     connect(&arm,SIGNAL(elbowAngle_rad(double)),&r,SLOT(moveElbowArm(double)));
00071     connect(ui->ArmResetButton,SIGNAL(clicked()),&r,SLOT(ResetArm()));
00072     connect(&r,SIGNAL(arm_model(bool,bool,bool,bool)),&arm,SLOT(setModel(bool,bool,bool,bool)));
00073     connect(&arm,SIGNAL(theta1(double)),ui->lcdNumber,SLOT(display(double))); //display shoulder angle
00074     connect(&arm,SIGNAL(theta2(double)),ui->lcdNumber_2,SLOT(display(double))); //display elbow angle
00075     connect(&wrist,SIGNAL(angle(double)),ui->lcdNumber_3,SLOT(display(double))); //display wrist angle
00076     connect(ui->radioButton_5,SIGNAL(toggled(bool)),&arm,SLOT(shoulder_degree(bool))); //choose to display shoulder angle in degree or radian
00077     connect(ui->radioButton_7,SIGNAL(toggled(bool)),&arm,SLOT(elbow_degree(bool)));//choose to display elbow angle in degree or radian
00078     connect(ui->radioButton_3,SIGNAL(toggled(bool)),&wrist,SLOT(degree(bool))); //choose to display the wrist angle in degree or radian
00079     connect(ui->radioButton,SIGNAL(toggled(bool)),&r,SLOT(moveGripper(bool)));//open or close the gripper
00080     connect(ui->radioButton_9,SIGNAL(toggled(bool)),&arm,SLOT(Corobot(bool)));//gives robot information(Corobot or Explorer) to the arm widget
00081     connect(&wrist,SIGNAL(angle_rad(float)),&r,SLOT(turnWrist(float))); //turn wrist if the wrist widget angle changed
00082 
00083     //***************************************************************************
00084         //MISC tab
00085     //***************************************************************************
00086     //Bumper information
00087     connect(&r,SIGNAL(bumper_update(int,int,int,int)),this,SLOT(bumper_update_slot(int,int,int,int)));
00088 
00089     //IR data
00090     connect(&r,SIGNAL(irData(double,double)),this,SLOT(irdata_update_slot(double,double)));
00091     connect(&r,SIGNAL(irData(double,double)),&hokuyo,SLOT(IR_update(double,double)));
00092 
00093     //Spatial data
00094     connect(&r,SIGNAL(imu_data(double,double,double,double,double,double)),this,SLOT(imu_update_slot(double,double,double,double,double,double)));
00095     connect(&r,SIGNAL(magnetic_data(double,double,double)),this,SLOT(magnetic_update_slot(double,double,double)));
00096 
00097     //Battery
00098     connect(&r,SIGNAL(battery_percent(int)),ui->progressBar,SLOT(setValue(int))); //display the battery percent
00099     connect(&r,SIGNAL(battery_volts(double)),ui->lcdNumber_8,SLOT(display(double)));//display the battery voltage
00100 
00101     //****************************************************************************
00102     // GPS
00103     connect(ui->spinBox_2,SIGNAL(valueChanged(int)),(QObject*)&gps,SLOT(set_zoom(int))); //set zoom value for the gps map
00104     connect(&gps,SIGNAL(url_changed(QUrl)),this,SLOT(change_url(QUrl))); //set the rl to the web viewer
00105     connect(ui->comboBox,SIGNAL(currentIndexChanged(QString)),&gps,SLOT(set_map_type(QString)));//set the gps map type
00106     connect(ui->save_gps,SIGNAL(clicked()),&gps,SLOT(save_clicked())); //save button clicked
00107     connect(ui->start_gps,SIGNAL(clicked()),&gps,SLOT(start_clicked()));//start button clicked
00108     connect(ui->sto_gps,SIGNAL(clicked()),&gps,SLOT(stop_clicked()));//stop button clicked
00109     connect(ui->load_gps,SIGNAL(clicked()),&gps,SLOT(load_clicked())); //load button clicked
00110     connect(&r,SIGNAL(gps_lat(double)),ui->lcdNumber_4,SLOT(display(double))); //display the latitude
00111     connect(&r,SIGNAL(gps_lon(double)),ui->lcdNumber_5,SLOT(display(double)));//display the longitude
00112     connect(&r,SIGNAL(gps_coord(double,double)),&gps,SLOT(update_coord(double,double))); //gives new coordinate to the gps widget
00113     connect(this,SIGNAL(size_changed()),&gps,SLOT(check_size()));//adjust the size of the map with the size of the window
00114     connect(ui->listWidget,SIGNAL(itemSelectionChanged()),&gps,SLOT(selection_changed()));//selection of the itinerary changed
00115 
00116 
00117     //****************************************************************************
00118     //Pan/Tilt control
00119 
00120     connect(ui->Pan_control_bar,SIGNAL(valueChanged(int)),&r,SLOT(Pan_control(int)));
00121     connect(ui->Tilt_control_bar,SIGNAL(valueChanged(int)),&r,SLOT(Tilt_control(int)));
00122     connect(ui->PanTilt_Reset,SIGNAL(clicked()),this,SLOT(Pan_Tilt_reset()));
00123 
00124     //****************************************************************************
00125     //Cameras
00126     connect(&r,SIGNAL(update_ptzcam(QImage)),this,SLOT(update_ptz(QImage))); //force to update the ptz cam
00127     connect(&r,SIGNAL(update_mapimage(QImage)),this,SLOT(update_map(QImage))); //force to update the ptz cam
00128     connect(&r,SIGNAL(update_rearcam(QImage)),this,SLOT(update_rear(QImage))); //force to update the reat cam scene
00129     connect(&r,SIGNAL(update_kinectRGBcam(QImage)),this,SLOT(update_kinectRGB(QImage))); //force to update the kinect RGB scene
00130     connect(&r,SIGNAL(update_kinectDepthcam(QImage)),this,SLOT(update_kinectDepth(QImage))); //force to update the kinect Depth scene
00131     connect(ui->camera, SIGNAL(currentChanged(int)),&r, SLOT(currentCameraTabChanged(int))); //Subscribe only to the camera topic we are interested in
00132 
00133     //***************************************************************************
00134     //Main motor control
00135 
00136     connect(ui->Forward, SIGNAL(pressed()), &r, SLOT(increase_speed()));
00137     connect(ui->Forward, SIGNAL(released()), &r, SLOT(decrease_speed()));
00138     connect(ui->BACKWARD, SIGNAL(pressed()), &r, SLOT(increase_backward_speed()));
00139     connect(ui->BACKWARD, SIGNAL(released()), &r, SLOT(decrease_speed()));
00140 
00141     connect(ui->TURNLEFT,SIGNAL(pressed()),&r,SLOT(turn_left()));
00142     connect(ui->TURNRIGHT,SIGNAL(pressed()),&r,SLOT(turn_right()));
00143     connect(ui->TURNLEFT,SIGNAL(released()),&r,SLOT(stop_turn()));
00144     connect(ui->TURNRIGHT,SIGNAL(released()),&r,SLOT(stop_turn()));
00145     connect(ui->STOP,SIGNAL(clicked()),&r,SLOT(motor_stop()));
00146 
00147     connect(ui->speed_fast, SIGNAL(toggled(bool)), &r, SLOT(setSpeedFast(bool)));
00148     connect(ui->speed_moderate, SIGNAL(toggled(bool)), &r, SLOT(setSpeedModerate(bool)));
00149     connect(ui->speed_slow, SIGNAL(toggled(bool)), &r, SLOT(setSpeedSlow(bool)));
00150 
00151     connect(ui->Forward_2, SIGNAL(pressed()), &r, SLOT(increase_speed()));
00152     connect(ui->Forward_2, SIGNAL(released()), &r, SLOT(decrease_speed()));
00153     connect(ui->BACKWARD_2, SIGNAL(pressed()), &r, SLOT(increase_backward_speed()));
00154     connect(ui->BACKWARD_2, SIGNAL(released()), &r, SLOT(decrease_speed()));
00155 
00156     connect(ui->TURNLEFT_2,SIGNAL(pressed()),&r,SLOT(turn_left()));
00157     connect(ui->TURNRIGHT_2,SIGNAL(pressed()),&r,SLOT(turn_right()));
00158     connect(ui->TURNLEFT_2,SIGNAL(released()),&r,SLOT(stop_turn()));
00159     connect(ui->TURNRIGHT_2,SIGNAL(released()),&r,SLOT(stop_turn()));
00160     connect(ui->STOP_2,SIGNAL(clicked()),&r,SLOT(motor_stop()));
00161 
00162     connect(ui->speed_fast_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedFast(bool)));
00163     connect(ui->speed_moderate_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedModerate(bool)));
00164     connect(ui->speed_slow_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedSlow(bool)));
00165 
00166 
00167     //*******************************************************************************
00168     //Hokuyo update Tab
00169     connect(&r,SIGNAL(hokuyo_update(Hokuyo_Points*)),&hokuyo,SLOT(hokuyo_update(Hokuyo_Points*)));
00170 
00171     //buttons configuration
00172     connect(ui->ShowLRFlines,SIGNAL(clicked()),this,SLOT(showLRFlines()));
00173     connect(ui->ShowIRdata,SIGNAL(stateChanged(int)),this,SLOT(showIRdata(int)));
00174     connect(ui->showLRF,SIGNAL(stateChanged(int)),this,SLOT(showLRFdata(int)));
00175 
00176     //*******************************************************************************
00177 
00178     connect(&r,SIGNAL(velocity_info(double,double)),this,SLOT(encoder_info_update(double,double)));
00179 
00180     connect(ui->quitButton,SIGNAL(clicked()),this,SLOT(close()));
00181 
00182     //*******************************************************************************
00183     //Motor Control Toggle
00184     connect(ui->MotorControlToggle,SIGNAL(stateChanged(int)),this,SLOT(motor_control_toggle(int)));
00185 
00186     //***********************************************************************************
00187 
00188 
00189     //create different scenes
00190     QGraphicsScene *scene = new QGraphicsScene(this);
00191     scene->setItemIndexMethod(QGraphicsScene::NoIndex);
00192     scene->setSceneRect(0, 0, 640, 480);
00193 
00194     QGraphicsScene *scene3 = new QGraphicsScene(this);
00195     scene3->setItemIndexMethod(QGraphicsScene::NoIndex);
00196     scene3->setSceneRect(0, 00, 640, 480);
00197 
00198     QGraphicsScene *scene4 = new QGraphicsScene(this);
00199     scene4->setItemIndexMethod(QGraphicsScene::NoIndex);
00200     scene4->setSceneRect(0, 00, 640, 480);
00201 
00202     QGraphicsScene *scene10 = new QGraphicsScene(this);
00203     scene10->setItemIndexMethod(QGraphicsScene::NoIndex);
00204     scene10->setSceneRect(0, 00, 640, 480);
00205 
00206     QGraphicsScene *scene2 = new QGraphicsScene(this);
00207     scene2->setItemIndexMethod(QGraphicsScene::NoIndex);
00208     scene2->setSceneRect(0, 00, 2048, 2048);
00209 
00210     QGraphicsScene *scene5 = new QGraphicsScene(this);
00211     scene5->setItemIndexMethod(QGraphicsScene::NoIndex);
00212     scene5->setSceneRect(0, 00, 640, 480);
00213 
00214 
00215     //set scenes to the graphicsView widget
00216 
00217         scene10->setSceneRect(0,0,640,480);
00218         image_rear_cam.setPos(0,0);
00219         scene10->addItem(&image_rear_cam);
00220 
00221         scene2->setSceneRect(0,0,2048,2048);
00222         image_map_image.setPos(0,0);
00223         scene2->addItem(&image_map_image);
00224 
00225         scene5->setSceneRect(0,0,640,480);
00226         image_front_cam.setPos(0,0);
00227         scene5->addItem(&image_front_cam);
00228 
00229         scene->setSceneRect(0,0,640,480);
00230         image_ptz_cam.setPos(0,0);
00231         scene->addItem(&image_ptz_cam);
00232 
00233         scene4->setSceneRect(0,0,640,480);
00234         image_kinect_rgb.setPos(0,0);
00235         scene4->addItem(&image_kinect_rgb);
00236 
00237         scene3->setSceneRect(0,0,640,480);
00238         image_kinect_depth.setPos(0,0);
00239         scene3->addItem(&image_kinect_depth);
00240 
00241         ui->graphicsView->setScene(scene);
00242         ui->graphicsView_2->setScene(scene4);
00243         ui->graphicsView_3->setScene(scene3);
00244         ui->graphicsView_10->setScene(scene10);
00245         ui->mapView->setScene(scene2);
00246         ui->frontView->setScene(scene5);
00247 
00248     connect(&r,SIGNAL(save_image(bool)), &image_ptz_cam, SLOT(saveImage(bool))); //order to save the current image from the front camera.
00249 
00250 
00251 next_gripper_state = true;
00252 
00253 
00254 //change focus policy to always be able to move robot with the keyboard
00255 ui->camera->setFocusPolicy(Qt::NoFocus);
00256 this->setFocusPolicy(Qt::StrongFocus);
00257 
00258 ui->tabWidget_5->setFocus();
00259 }
00260 
00261 MainWindow::~MainWindow()
00262 {
00263     delete ui;
00264 }
00265 
00266 void MainWindow::setArguments(int argc_, char *argv_[])
00267 {
00268         argc = argc_;
00269         argv = argv_;
00270 }
00271 
00272 
00273 void MainWindow::connect_clicked(){ // executed when the connect button is pushed
00274     ui->connect->setText("Disconnect");
00275     ui->connect->setEnabled(false);
00276     // Initialize the ROS node
00277     if ( ui->environmentcheckbox->isChecked() ) {
00278             r.init(argc, argv);
00279     } else {
00280             r.init(argc, argv, ui->Master->text().toStdString(),ui->Host->text().toStdString());
00281             ui->Master->setReadOnly(true);
00282             ui->Host->setReadOnly(true);
00283     }
00284 }
00285 
00286 void MainWindow::resizeEvent(QResizeEvent *){//execute this function when the window size changes
00287     emit size_changed();
00288 }
00289 
00290 void MainWindow::change_url(QUrl url)//set url to the web viewer
00291 {
00292         if(gpsUrlTImer.isValid() == false || gpsUrlTImer.elapsed()>3000) //We don't want to do more than one querry every 3s
00293         {
00294                 gpsUrlTImer.restart();
00295                 gpsUrlTImer.start();
00296                 //ui->webView->setUrl(url); Removed because we don't want to break the Google's terms and conditions
00297         }
00298 }
00299 
00300 
00301 
00302 void MainWindow::update_ptz(QImage image) //order the ptz camera scene to update
00303 {
00304         ((Image*)(ui->graphicsView->scene()->items().at(0)))->setImage(image);
00305     ui->graphicsView->scene()->update(0,0,ui->graphicsView->scene()->width(),ui->graphicsView->scene()->height());
00306 
00307     ((Image*)(ui->frontView->scene()->items().at(0)))->setImage(image);
00308     ui->frontView->scene()->update(0,0,ui->frontView->scene()->width(),ui->frontView->scene()->height());
00309 }
00310 
00311 void MainWindow::update_map(QImage image) //order the map image scene to update
00312 {
00313     ((Image*)(ui->mapView->scene()->items().at(0)))->setImage(image);
00314     ui->mapView->scene()->setSceneRect(0,0,image.height(),image.width());
00315     ui->mapView->scene()->update(0,0,ui->mapView->scene()->width(),ui->mapView->scene()->height());
00316 }
00317 
00318 void MainWindow::update_rear(QImage image) //order the rear camera scene to update
00319 {
00320         ((Image*)(ui->graphicsView_10->scene()->items().at(0)))->setImage(image);
00321     ui->graphicsView_10->scene()->update(0,0,ui->graphicsView_10->scene()->width(),ui->graphicsView_10->scene()->height());
00322 }
00323 
00324 void MainWindow::update_kinectRGB(QImage image) //order the kinect RGB camera scene to update
00325 {
00326         ((Image*)(ui->graphicsView_2->scene()->items().at(0)))->setImage(image);
00327     ui->graphicsView_2->scene()->update(0,0,ui->graphicsView_2->scene()->width(),ui->graphicsView_2->scene()->height());
00328 }
00329 
00330 void MainWindow::update_kinectDepth(QImage image) //order the kinect Depth camera scene to update
00331 {
00332         ((Image*)(ui->graphicsView_3->scene()->items().at(0)))->setImage(image);
00333     ui->graphicsView_3->scene()->update(0,0,ui->graphicsView_3->scene()->width(),ui->graphicsView_3->scene()->height());
00334 }
00335 
00336 
00337 
00338 void MainWindow::keyReleaseEvent(QKeyEvent *event){//executed each time a keyboard key is release, to control the robot movements
00339 
00340     switch (event->key()) {
00341         case Qt::Key_W:
00342             if(!event->isAutoRepeat())
00343             {
00344                 r.decrease_speed();
00345             }
00346             break;
00347         case Qt::Key_S:
00348             if(!event->isAutoRepeat())
00349             {
00350                 r.decrease_speed();
00351             }
00352             break;
00353         case Qt::Key_D:
00354             if(!event->isAutoRepeat())
00355             {
00356                 r.stop_turn();
00357             }
00358             break;
00359         case Qt::Key_A:
00360             if(!event->isAutoRepeat())
00361             {
00362                 r.stop_turn();
00363             }
00364             break;
00365         default:
00366             QWidget::keyReleaseEvent(event);
00367     }
00368 }
00369 
00370 void MainWindow::keyPressEvent(QKeyEvent *event){//executed each time a keyboard key is pushed, to control the robot movements
00371     switch (event->key()) {
00372     case Qt::Key_W:
00373         if(!event->isAutoRepeat())
00374         {
00375                 r.increase_speed();
00376         }
00377         break;
00378     case Qt::Key_S:
00379         if(!event->isAutoRepeat())
00380         {
00381                 r.increase_backward_speed();
00382         }
00383         break;
00384     case Qt::Key_D:
00385         if(!event->isAutoRepeat())
00386         {
00387                 r.turn_right();
00388         }
00389         break;
00390     case Qt::Key_A:
00391         if(!event->isAutoRepeat())
00392         {
00393                 r.turn_left();
00394         }
00395         break;
00396     case Qt::Key_Left:
00397         if(r.pan >= -65) 
00398                 ui->Pan_control_bar->setValue(r.pan - 5);
00399         else if (r.pan > -70)
00400                 ui->Pan_control_bar->setValue(-70);
00401         break;
00402     case Qt::Key_Right:
00403         if(r.pan <= 65) 
00404                 ui->Pan_control_bar->setValue(r.pan + 5);
00405         else if (r.pan < 70)
00406                 ui->Pan_control_bar->setValue(70);
00407         break;
00408     case Qt::Key_Up:
00409         if(r.tilt <= 25) 
00410                 ui->Tilt_control_bar->setValue(r.tilt + 5);
00411         else if (r.tilt < 30)
00412                 ui->Tilt_control_bar->setValue(30);
00413         break;
00414     case Qt::Key_Down:
00415         if(r.tilt >= -25) 
00416                 ui->Tilt_control_bar->setValue(r.tilt - 5);
00417         else if (r.tilt > -30)
00418                 ui->Tilt_control_bar->setValue(-30);
00419         break;
00420     case Qt::Key_J:
00421         arm.moveArmLeft();
00422         break;
00423     case Qt::Key_L:
00424         arm.moveArmRight();
00425         break;
00426     case Qt::Key_I:
00427         arm.moveArmUp();
00428         break;
00429     case Qt::Key_K:
00430         arm.moveArmDown();
00431         break;
00432     case Qt::Key_Space:
00433         r.motor_stop();
00434         if(next_gripper_state)
00435             r.closeGripper();
00436         else
00437             r.openGripper();
00438         next_gripper_state = !next_gripper_state;
00439         break;
00440     default:
00441         QWidget::keyPressEvent(event);
00442     }
00443 }
00444 
00445 
00446 void MainWindow::bumper_update_slot(int bumper1, int bumper2, int bumper3, int bumper4) // update bumper data
00447 {
00448     if(bumper1 != 0) ui->label_19->setText("Bumper 1 HIT!"); else ui->label_19->setText("Bumper 1 SAFE");
00449     if(bumper2 != 0) ui->label_24->setText("Bumper 2 HIT!"); else ui->label_24->setText("Bumper 2 SAFE");
00450     if(bumper3 != 0) ui->label_26->setText("Bumper 3 HIT!"); else ui->label_26->setText("Bumper 3 SAFE");
00451     if(bumper4 != 0) ui->label_40->setText("Bumper 4 HIT!"); else ui->label_40->setText("Bumper 4 SAFE");
00452 
00453 }
00454 
00455 
00456 
00457 void MainWindow::encoder_info_update(double linearVelocity,double angularVelocity) // update the encoder info on the interface
00458 {
00459     ui->linear_velocity->display(linearVelocity);
00460     ui->angular_velocity->display(angularVelocity);
00461 }
00462 
00463 
00464 void MainWindow::motor_control_toggle(int value) // interface the toggle button "Motor Control Disable"
00465 {
00466     if(value != 0)
00467     {
00468         ui->Forward->setEnabled(false);
00469         ui->BACKWARD->setEnabled(false);
00470         ui->TURNLEFT->setEnabled(false);
00471         ui->TURNRIGHT->setEnabled(false);
00472         ui->STOP->setEnabled(false);
00473         ui->frame->setEnabled(false);
00474         ui->frame_7->setEnabled(false);
00475         ui->frame_8->setEnabled(false);
00476     }
00477 
00478     else
00479     {
00480         ui->Forward->setEnabled(true);
00481         ui->BACKWARD->setEnabled(true);
00482         ui->TURNLEFT->setEnabled(true);
00483         ui->TURNRIGHT->setEnabled(true);
00484         ui->STOP->setEnabled(true);
00485         ui->frame->setEnabled(true);
00486         ui->frame_7->setEnabled(true);
00487         ui->frame_8->setEnabled(true);
00488     }
00489 
00490 }
00491 
00492 void MainWindow::irdata_update_slot(double ir01, double ir02) //update the onscreen value of the infrared sensor
00493 {
00494     ui->lcdNumber_IR01->display(ir01);
00495     ui->lcdNumber_IR02->display(ir02);
00496 }
00497 
00498 void MainWindow::imu_update_slot(double acc_x, double acc_y, double acc_z, double ang_x, double ang_y, double ang_z) //update the imu values on the interface
00499 {
00500     ui->lcdNumber_acc_x->display(acc_x);
00501     ui->lcdNumber_acc_y->display(acc_y);
00502     ui->lcdNumber_acc_z->display(acc_z);
00503     ui->lcdNumber_ang_x->display(ang_x);
00504     ui->lcdNumber_ang_y->display(ang_y);
00505     ui->lcdNumber_any_z->display(ang_z);
00506 }
00507 
00508 void MainWindow::magnetic_update_slot(double mag_x, double mag_y, double mag_z) //update the imu values on the interface
00509 {
00510     ui->lcdNumber_mag_x->display(mag_x);
00511     ui->lcdNumber_mag_y->display(mag_y);
00512     ui->lcdNumber_mag_z->display(mag_z);
00513 }
00514 
00515 void MainWindow::showLRFlines() // Interface the show line button in the rangefinding interface
00516 {
00517     QString string1 = "No Lines";
00518     QString string2 = "Show Lines";
00519 
00520     if(LRF_lines_show == false)
00521     {
00522         ui->ShowLRFlines->setText(string1);
00523         LRF_lines_show = true;
00524         hokuyo.showlines = true;
00525     }
00526     else
00527     {
00528         LRF_lines_show = false;
00529         ui->ShowLRFlines->setText(string2);
00530         hokuyo.showlines = false;
00531     }
00532 
00533 }
00534 
00535 void MainWindow::showIRdata(int value) // Interface the show ir data button in the rangefinder interface
00536 {
00537 
00538     if(value != 0)
00539     {
00540         hokuyo.showIR = true;
00541         hokuyo.showLRF = false;
00542         ui->showLRF->setEnabled(false);
00543     }
00544 
00545     else
00546     {
00547         hokuyo.showIR = false;
00548         //hokuyo.showLRF = false;
00549         ui->showLRF->setEnabled(true);
00550     }
00551 
00552 }
00553 
00554 void MainWindow::showLRFdata(int value) // Interface the show LRF button in the rangefinder interface
00555 {
00556     if(value != 0)
00557     {
00558         hokuyo.showIR = false;
00559         hokuyo.showLRF = true;
00560         ui->ShowIRdata->setEnabled(false);
00561     }
00562 
00563     else
00564     {
00565         //hokuyo.showIR = false;
00566         hokuyo.showLRF = false;
00567         ui->ShowIRdata->setEnabled(true);
00568     }
00569 
00570 
00571 }
00572 
00573 void MainWindow::Pan_Tilt_reset()// ask the ros node to reset the pan and tilt position of the camera
00574 {
00575         r.Pan_control(0);
00576         r.Tilt_control(0);
00577         ui-> Pan_control_bar->setValue(0);
00578         ui-> Tilt_control_bar ->setValue(0);
00579 }


corobot_teleop
Author(s):
autogenerated on Wed Aug 26 2015 11:09:59