00001 #include "mainwindow.h"
00002 #include "ui_mainwindow.h"
00003 #include "ImageBig.h"
00004 #include "Image.h"
00005
00006 #ifdef Q_WS_WIN
00007 #include "windows.h"
00008 #include "mmsystem.h"
00009 #endif
00010
00011
00012 MainWindow::MainWindow(QWidget *parent) :
00013 QMainWindow(parent),
00014 ui(new Ui::MainWindow)
00015 {
00016
00017 r.setParent(this);
00018 ui->setupUi(this);
00019 arm.setParent(ui->frame);
00020 arm_rotation.setParent(ui->frame_6);
00021 gripper.setParent(ui->frame_7);
00022 wrist.setParent(ui->frame_8);
00023 gps.setParent(ui->webView);
00024 gps.setList(ui->listWidget);
00025 hokuyo.setParent(ui->frame_hokuyo);
00026 gpsUrlTImer.invalidate();
00027
00028
00029 ui->tabWidget_5->setFocus();
00030
00031 LRF_lines_show = false;
00032 IR_data_show = false;
00033
00034
00035
00036
00037
00038 connect(&arm,SIGNAL(theta1(double)),ui->lcdNumber,SLOT(display(double)));
00039 connect(&arm,SIGNAL(theta2(double)),ui->lcdNumber_2,SLOT(display(double)));
00040 connect(&wrist,SIGNAL(angle(double)),ui->lcdNumber_3,SLOT(display(double)));
00041 connect(ui->radioButton_5,SIGNAL(toggled(bool)),&arm,SLOT(shoulder_degree(bool)));
00042 connect(ui->radioButton_7,SIGNAL(toggled(bool)),&arm,SLOT(elbow_degree(bool)));
00043 connect(ui->radioButton_3,SIGNAL(toggled(bool)),&wrist,SLOT(degree(bool)));
00044
00045
00046 connect(ui->spinBox_2,SIGNAL(valueChanged(int)),(QObject*)&gps,SLOT(set_zoom(int)));
00047 connect(&gps,SIGNAL(url_changed(QUrl)),this,SLOT(change_url(QUrl)));
00048 connect(ui->comboBox,SIGNAL(currentIndexChanged(QString)),&gps,SLOT(set_map_type(QString)));
00049 connect(ui->radioButton,SIGNAL(toggled(bool)),&r,SLOT(moveGripper(bool)));
00050 connect(ui->radioButton_9,SIGNAL(toggled(bool)),&arm,SLOT(Corobot(bool)));
00051 connect(ui->radioButton_9,SIGNAL(toggled(bool)),&armCircle,SLOT(Corobot(bool)));
00052
00053 connect(ui->radioButton_9,SIGNAL(toggled(bool)),&r,SLOT(corobot(bool)));
00054
00055
00056
00057
00058 connect(&r,SIGNAL(gps_lat(double)),ui->lcdNumber_4,SLOT(display(double)));
00059 connect(&r,SIGNAL(gps_lon(double)),ui->lcdNumber_5,SLOT(display(double)));
00060 connect(&r,SIGNAL(gps_coord(double,double)),&gps,SLOT(update_coord(double,double)));
00061 connect(&r,SIGNAL(griperState(int)),&gripper,SLOT(setState(int)));
00062 connect(&wrist,SIGNAL(angle_rad(float)),&r,SLOT(turnWrist(float)));
00063
00064
00065 connect(ui->connect,SIGNAL(clicked()),this,SLOT(connect_clicked()));
00066 connect(&arm,SIGNAL(posarm(float,float)),&armCircle,SLOT(setpos(float,float)));
00067
00068
00069 connect(this,SIGNAL(size_changed()),&gps,SLOT(check_size()));
00070
00071 connect(ui->save_gps,SIGNAL(clicked()),&gps,SLOT(save_clicked()));
00072 connect(ui->start_gps,SIGNAL(clicked()),&gps,SLOT(start_clicked()));
00073 connect(ui->sto_gps,SIGNAL(clicked()),&gps,SLOT(stop_clicked()));
00074 connect(ui->load_gps,SIGNAL(clicked()),&gps,SLOT(load_clicked()));
00075
00076 connect(ui->listWidget,SIGNAL(itemSelectionChanged()),&gps,SLOT(selection_changed()));
00077
00078 connect(&r,SIGNAL(battery_percent(int)),ui->progressBar,SLOT(setValue(int)));
00079 connect(&r,SIGNAL(battery_volts(double)),ui->lcdNumber_8,SLOT(display(double)));
00080
00081 connect(&r,SIGNAL(update_ptzcam(QImage)),this,SLOT(update_ptz(QImage)));
00082 connect(&r,SIGNAL(update_mapimage(QImage)),this,SLOT(update_map(QImage)));
00083 connect(&r,SIGNAL(update_rearcam(QImage)),this,SLOT(update_rear(QImage)));
00084 connect(&r,SIGNAL(update_kinectRGBcam(QImage)),this,SLOT(update_kinectRGB(QImage)));
00085 connect(&r,SIGNAL(update_kinectDepthcam(QImage)),this,SLOT(update_kinectDepth(QImage)));
00086 connect(ui->camera, SIGNAL(currentChanged(int)),&r, SLOT(currentCameraTabChanged(int)));
00087
00088
00089
00090 connect(&arm,SIGNAL(shoulderAngle_rad(double)),&r,SLOT(moveShoulderArm(double)));
00091 connect(&arm_rotation,SIGNAL(armAngle_rad(double)),&r,SLOT(rotateArm(double)));
00092 connect(&arm,SIGNAL(elbowAngle_rad(double)),&r,SLOT(moveElbowArm(double)));
00093
00094 connect(ui->ArmResetButton,SIGNAL(clicked()),&r,SLOT(ResetArm()));
00095 connect(&r,SIGNAL(arm_model(bool,bool,bool,bool)),&arm,SLOT(setModel(bool,bool,bool,bool)));
00096
00097
00098
00099
00100
00101 connect(&r,SIGNAL(bumper_update(int,int,int,int)),this,SLOT(bumper_update_slot(int,int,int,int)));
00102
00103
00104 connect(&r,SIGNAL(irData(double,double)),this,SLOT(irdata_update_slot(double,double)));
00105 connect(&r,SIGNAL(irData(double,double)),&hokuyo,SLOT(IR_update(double,double)));
00106
00107
00108 connect(&r,SIGNAL(spatial_data(double,double,double,double,double,double,double,double,double)),this,SLOT(spatial_update_slot(double,double,double,double,double,double,double,double,double)));
00109
00110
00111
00112
00113
00114
00115
00116
00117 connect(ui->Pan_control_bar,SIGNAL(valueChanged(int)),this,SLOT(Pan_control(int)));
00118 connect(ui->Tilt_control_bar,SIGNAL(valueChanged(int)),this,SLOT(Tilt_control(int)));
00119 connect(ui->PanTilt_Reset,SIGNAL(clicked()),this,SLOT(Pan_Tilt_reset()));
00120
00121
00122
00123
00124
00125
00126
00127 connect(ui->Forward, SIGNAL(pressed()), &r, SLOT(increase_speed()));
00128 connect(ui->Forward, SIGNAL(released()), &r, SLOT(decrease_speed()));
00129 connect(ui->BACKWARD, SIGNAL(pressed()), &r, SLOT(increase_backward_speed()));
00130 connect(ui->BACKWARD, SIGNAL(released()), &r, SLOT(decrease_speed()));
00131
00132 connect(ui->TURNLEFT,SIGNAL(pressed()),&r,SLOT(turn_left()));
00133 connect(ui->TURNRIGHT,SIGNAL(pressed()),&r,SLOT(turn_right()));
00134 connect(ui->TURNLEFT,SIGNAL(released()),&r,SLOT(stop_turn()));
00135 connect(ui->TURNRIGHT,SIGNAL(released()),&r,SLOT(stop_turn()));
00136 connect(ui->STOP,SIGNAL(clicked()),&r,SLOT(motor_stop()));
00137
00138 connect(ui->speed_fast, SIGNAL(toggled(bool)), &r, SLOT(setSpeedFast(bool)));
00139 connect(ui->speed_moderate, SIGNAL(toggled(bool)), &r, SLOT(setSpeedModerate(bool)));
00140 connect(ui->speed_slow, SIGNAL(toggled(bool)), &r, SLOT(setSpeedSlow(bool)));
00141
00142 connect(ui->Forward_2, SIGNAL(pressed()), &r, SLOT(increase_speed()));
00143 connect(ui->Forward_2, SIGNAL(released()), &r, SLOT(decrease_speed()));
00144 connect(ui->BACKWARD_2, SIGNAL(pressed()), &r, SLOT(increase_backward_speed()));
00145 connect(ui->BACKWARD_2, SIGNAL(released()), &r, SLOT(decrease_speed()));
00146
00147 connect(ui->TURNLEFT_2,SIGNAL(pressed()),&r,SLOT(turn_left()));
00148 connect(ui->TURNRIGHT_2,SIGNAL(pressed()),&r,SLOT(turn_right()));
00149 connect(ui->TURNLEFT_2,SIGNAL(released()),&r,SLOT(stop_turn()));
00150 connect(ui->TURNRIGHT_2,SIGNAL(released()),&r,SLOT(stop_turn()));
00151 connect(ui->STOP_2,SIGNAL(clicked()),&r,SLOT(motor_stop()));
00152
00153 connect(ui->speed_fast_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedFast(bool)));
00154 connect(ui->speed_moderate_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedModerate(bool)));
00155 connect(ui->speed_slow_2, SIGNAL(toggled(bool)), &r, SLOT(setSpeedSlow(bool)));
00156
00157
00158
00159
00160
00161
00162 connect(&r,SIGNAL(hokuyo_update(Hokuyo_Points*)),&hokuyo,SLOT(hokuyo_update(Hokuyo_Points*)));
00163
00164
00165 connect(ui->ShowLRFlines,SIGNAL(clicked()),this,SLOT(showLRFlines()));
00166 connect(ui->ShowIRdata,SIGNAL(stateChanged(int)),this,SLOT(showIRdata(int)));
00167 connect(ui->showLRF,SIGNAL(stateChanged(int)),this,SLOT(showLRFdata(int)));
00168
00169
00170
00171 connect(&r,SIGNAL(velocity_info(double,double)),this,SLOT(encoder_info_update(double,double)));
00172
00173 connect(ui->quitButton,SIGNAL(clicked()),this,SLOT(close()));
00174
00175
00176
00177 connect(ui->MotorControlToggle,SIGNAL(stateChanged(int)),this,SLOT(motor_control_toggle(int)));
00178
00179
00180
00181
00182
00183 QGraphicsScene *scene = new QGraphicsScene(this);
00184 scene->setItemIndexMethod(QGraphicsScene::NoIndex);
00185 scene->setSceneRect(0, 0, 640, 480);
00186
00187 QGraphicsScene *scene3 = new QGraphicsScene(this);
00188 scene3->setItemIndexMethod(QGraphicsScene::NoIndex);
00189 scene3->setSceneRect(0, 00, 640, 480);
00190
00191 QGraphicsScene *scene4 = new QGraphicsScene(this);
00192 scene4->setItemIndexMethod(QGraphicsScene::NoIndex);
00193 scene4->setSceneRect(0, 00, 640, 480);
00194
00195 QGraphicsScene *scene10 = new QGraphicsScene(this);
00196 scene10->setItemIndexMethod(QGraphicsScene::NoIndex);
00197 scene10->setSceneRect(0, 00, 640, 480);
00198
00199 QGraphicsScene *scene2 = new QGraphicsScene(this);
00200 scene2->setItemIndexMethod(QGraphicsScene::NoIndex);
00201 scene2->setSceneRect(0, 00, 2048, 2048);
00202
00203 QGraphicsScene *scene5 = new QGraphicsScene(this);
00204 scene5->setItemIndexMethod(QGraphicsScene::NoIndex);
00205 scene5->setSceneRect(0, 00, 640, 480);
00206
00207
00208
00209
00210
00211 ui->graphicsView->setScene(scene);
00212
00213 ui->graphicsView_2->setScene(scene4);
00214
00215 ui->graphicsView_3->setScene(scene3);
00216
00217 ui->graphicsView_10->setScene(scene10);
00218 ui->mapView->setScene(scene2);
00219 ui->frontView->setScene(scene5);
00220
00221
00222
00223
00224
00225
00226
00227 next_gripper_state = true;
00228
00229
00230
00231
00232
00233
00234
00235
00236 ui->camera->setFocusPolicy(Qt::NoFocus);
00237
00238 this->setFocusPolicy(Qt::StrongFocus);
00239
00240
00241
00242
00243 r.add_rear_cam_scene(ui->graphicsView_10->scene());
00244 r.add_ptz_cam_scene(ui->graphicsView->scene());
00245 r.add_kinect_rgb_scene(ui->graphicsView_2->scene());
00246 r.add_kinect_depth_scene(ui->graphicsView_3->scene());
00247 r.add_map_image_scene(ui->mapView->scene());
00248 r.add_front_image_scene(ui->frontView->scene());
00249
00250
00251
00252
00253 ui->tabWidget_5->setFocus();
00254
00255
00256
00257 }
00258
00259 MainWindow::~MainWindow()
00260 {
00261 delete ui;
00262 }
00263
00264
00265 void MainWindow::connect_clicked(){
00266 ui->connect->setText("Disconnect");
00267 ui->connect->setEnabled(false);
00268 if ( ui->environmentcheckbox->isChecked() ) {
00269 r.init();
00270 } else {
00271 r.init(ui->Master->text().toStdString(),ui->Host->text().toStdString());
00272 ui->Master->setReadOnly(true);
00273 ui->Host->setReadOnly(true);
00274 }
00275 }
00276
00277 void MainWindow::resizeEvent(QResizeEvent *){
00278 emit size_changed();
00279 }
00280
00281 void MainWindow::change_url(QUrl url)
00282 {
00283 if(gpsUrlTImer.isValid() == false || gpsUrlTImer.elapsed()>3000)
00284 {
00285 gpsUrlTImer.restart();
00286 gpsUrlTImer.start();
00287
00288 }
00289 }
00290
00291 void MainWindow::update_ptz(QImage image)
00292 {
00293
00294 ((Image*)(ui->graphicsView->scene()->items().at(0)))->setImage(image);
00295 ui->graphicsView->scene()->update(0,0,ui->graphicsView->scene()->width(),ui->graphicsView->scene()->height());
00296
00297
00298 ((Image*)(ui->frontView->scene()->items().at(0)))->setImage(image);
00299 ui->frontView->scene()->update(0,0,ui->frontView->scene()->width(),ui->frontView->scene()->height());
00300 }
00301
00302 void MainWindow::update_map(QImage image)
00303 {
00304 ((Image*)(ui->mapView->scene()->items().at(0)))->setImage(image);
00305 ui->mapView->scene()->update(0,0,ui->mapView->scene()->width(),ui->mapView->scene()->height());
00306 }
00307
00308 void MainWindow::update_rear(QImage image)
00309 {
00310
00311 ((Image*)(ui->graphicsView_10->scene()->items().at(0)))->setImage(image);
00312 ui->graphicsView_10->scene()->update(0,0,ui->graphicsView_10->scene()->width(),ui->graphicsView_10->scene()->height());
00313 }
00314
00315 void MainWindow::update_kinectRGB(QImage image)
00316 {
00317
00318 ((Image*)(ui->graphicsView_2->scene()->items().at(0)))->setImage(image);
00319 ui->graphicsView_2->scene()->update(0,0,ui->graphicsView_2->scene()->width(),ui->graphicsView_2->scene()->height());
00320 }
00321
00322 void MainWindow::update_kinectDepth(QImage image)
00323 {
00324
00325 ((Image*)(ui->graphicsView_3->scene()->items().at(0)))->setImage(image);
00326 ui->graphicsView_3->scene()->update(0,0,ui->graphicsView_3->scene()->width(),ui->graphicsView_3->scene()->height());
00327 }
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380
00381
00382
00383
00384 void MainWindow::keyReleaseEvent(QKeyEvent *event){
00385
00386 switch (event->key()) {
00387 case Qt::Key_W:
00388 if(!event->isAutoRepeat())
00389 {
00390 r.decrease_speed();
00391 }
00392 break;
00393 case Qt::Key_S:
00394 if(!event->isAutoRepeat())
00395 {
00396 r.decrease_speed();
00397 }
00398 break;
00399 case Qt::Key_D:
00400 if(!event->isAutoRepeat())
00401 {
00402 r.stop_turn();
00403 }
00404 break;
00405 case Qt::Key_A:
00406 if(!event->isAutoRepeat())
00407 {
00408 r.stop_turn();
00409 }
00410 break;
00411 default:
00412 QWidget::keyReleaseEvent(event);
00413 }
00414 }
00415
00416 void MainWindow::keyPressEvent(QKeyEvent *event){
00417 switch (event->key()) {
00418 case Qt::Key_W:
00419 if(!event->isAutoRepeat())
00420 {
00421 r.increase_speed();
00422 }
00423 break;
00424 case Qt::Key_S:
00425 if(!event->isAutoRepeat())
00426 {
00427 r.increase_backward_speed();
00428 }
00429 break;
00430 case Qt::Key_D:
00431 if(!event->isAutoRepeat())
00432 {
00433 r.turn_right();
00434 }
00435 break;
00436 case Qt::Key_A:
00437 if(!event->isAutoRepeat())
00438 {
00439 r.turn_left();
00440 }
00441 break;
00442 case Qt::Key_Left:
00443 if(r.pan >= -65)
00444 ui->Pan_control_bar->setValue(r.pan - 5);
00445 else if (r.pan > -70)
00446 ui->Pan_control_bar->setValue(-70);
00447 break;
00448 case Qt::Key_Right:
00449 if(r.pan <= 65)
00450 ui->Pan_control_bar->setValue(r.pan + 5);
00451 else if (r.pan < 70)
00452 ui->Pan_control_bar->setValue(70);
00453 break;
00454 case Qt::Key_Up:
00455 if(r.tilt <= 25)
00456 ui->Tilt_control_bar->setValue(r.tilt + 5);
00457 else if (r.tilt < 30)
00458 ui->Tilt_control_bar->setValue(30);
00459 break;
00460 case Qt::Key_Down:
00461 if(r.tilt >= -25)
00462 ui->Tilt_control_bar->setValue(r.tilt - 5);
00463 else if (r.tilt > -30)
00464 ui->Tilt_control_bar->setValue(-30);
00465 break;
00466 case Qt::Key_J:
00467 arm.moveArmLeft();
00468 break;
00469 case Qt::Key_L:
00470 arm.moveArmRight();
00471 break;
00472 case Qt::Key_I:
00473 arm.moveArmUp();
00474 break;
00475 case Qt::Key_K:
00476 arm.moveArmDown();
00477 break;
00478 case Qt::Key_Space:
00479 r.motor_stop();
00480 if(next_gripper_state)
00481 r.closeGripper();
00482 else
00483 r.openGripper();
00484 next_gripper_state = !next_gripper_state;
00485 break;
00486 default:
00487 QWidget::keyPressEvent(event);
00488 }
00489 }
00490
00491
00492 void MainWindow::bumper_update_slot(int bumper1, int bumper2, int bumper3, int bumper4)
00493 {
00494 if(bumper1 != 0) ui->label_19->setText("Bumper 1 HIT!"); else ui->label_19->setText("Bumper 1 SAFE");
00495 if(bumper2 != 0) ui->label_24->setText("Bumper 2 HIT!"); else ui->label_24->setText("Bumper 2 SAFE");
00496 if(bumper3 != 0) ui->label_26->setText("Bumper 3 HIT!"); else ui->label_26->setText("Bumper 3 SAFE");
00497 if(bumper4 != 0) ui->label_40->setText("Bumper 4 HIT!"); else ui->label_40->setText("Bumper 4 SAFE");
00498
00499 }
00500
00501 void MainWindow::Pan_control(int value)
00502 {
00503 r.pan = value;
00504 corobot_teleop::PanTilt msg;
00505 msg.pan = r.pan;
00506 msg.tilt = r.tilt;
00507 msg.reset = 0;
00508 r.pan_tilt_control.publish(msg);
00509 }
00510
00511 void MainWindow::Tilt_control(int value)
00512 {
00513 r.tilt = value;
00514 corobot_teleop::PanTilt msg;
00515 msg.pan = r.pan;
00516 msg.tilt = r.tilt;
00517 msg.reset = 0;
00518 r.pan_tilt_control.publish(msg);
00519 }
00520
00521 void MainWindow::Pan_Tilt_reset()
00522 {
00523 r.pan = 0;
00524 r.tilt = 0;
00525
00526 ui-> Pan_control_bar->setValue(0);
00527 ui-> Tilt_control_bar ->setValue(0);
00528
00529 corobot_teleop::PanTilt msg;
00530 msg.pan = r.pan;
00531 msg.tilt = r.tilt;
00532 msg.reset = 1;
00533 r.pan_tilt_control.publish(msg);
00534 }
00535
00536 void MainWindow::encoder_info_update(double linearVelocity,double angularVelocity)
00537 {
00538 ui->linear_velocity->display(linearVelocity);
00539 ui->angular_velocity->display(angularVelocity);
00540 }
00541
00542
00543
00544 void MainWindow::move_speed_select(int x)
00545 {
00546
00547 switch(x){
00548 case 1:
00549 r.left_motor_value = 1000;
00550 r.right_motor_value = 1000;
00551 r.move_speed_level = 1;
00552
00553
00554 break;
00555 case 2:
00556 r.left_motor_value = 1000;
00557 r.right_motor_value = 1000;
00558 r.move_speed_level = 2;
00559
00560
00561 break;
00562 case 3:
00563 r.left_motor_value = 1000;
00564 r.right_motor_value = 1000;
00565 r.move_speed_level = 3;
00566 break;
00567 case 4:
00568 r.left_motor_value = 1000;
00569 r.right_motor_value = 1000;
00570 r.move_speed_level = 4;
00571 break;
00572 default:
00573 r.move_speed_level = 0;
00574 r.left_motor_value = 1000;
00575 r.right_motor_value = 1000;
00576 }
00577 }
00578
00579 void MainWindow::turning_speed_select(int x)
00580 {
00581
00582 switch(x){
00583 case 1:
00584 r.left_motor_value = 1000;
00585 r.right_motor_value = 1000;
00586 r.turning_speed_level = 1;
00587
00588
00589 break;
00590 case 2:
00591 r.left_motor_value = 1000;
00592 r.right_motor_value = 1000;
00593 r.turning_speed_level = 2;
00594
00595
00596 break;
00597 case 3:
00598 r.left_motor_value = 1000;
00599 r.right_motor_value = 1000;
00600 r.turning_speed_level = 3;
00601 break;
00602 case 4:
00603 r.left_motor_value = 1000;
00604 r.right_motor_value = 1000;
00605 r.turning_speed_level = 4;
00606 break;
00607 default:
00608 r.turning_speed_level = 0;
00609 r.left_motor_value = 1000;
00610 r.right_motor_value = 1000;
00611 }
00612
00613 }
00614
00615 void MainWindow::motor_control_toggle(int value)
00616 {
00617 if(value != 0)
00618 {
00619 ui->Forward->setEnabled(false);
00620 ui->BACKWARD->setEnabled(false);
00621 ui->TURNLEFT->setEnabled(false);
00622 ui->TURNRIGHT->setEnabled(false);
00623 ui->STOP->setEnabled(false);
00624 ui->frame->setEnabled(false);
00625 ui->frame_7->setEnabled(false);
00626 ui->frame_8->setEnabled(false);
00627 }
00628
00629 else
00630 {
00631 ui->Forward->setEnabled(true);
00632 ui->BACKWARD->setEnabled(true);
00633 ui->TURNLEFT->setEnabled(true);
00634 ui->TURNRIGHT->setEnabled(true);
00635 ui->STOP->setEnabled(true);
00636 ui->frame->setEnabled(true);
00637 ui->frame_7->setEnabled(true);
00638 ui->frame_8->setEnabled(true);
00639 }
00640
00641 }
00642
00643 void MainWindow::irdata_update_slot(double ir01, double ir02)
00644 {
00645 ui->lcdNumber_IR01->display(ir01);
00646 ui->lcdNumber_IR02->display(ir02);
00647 }
00648
00649 void MainWindow::spatial_update_slot(double acc_x, double acc_y, double acc_z, double ang_x, double ang_y, double ang_z, double mag_x, double mag_y, double mag_z)
00650 {
00651 ui->lcdNumber_acc_x->display(acc_x);
00652 ui->lcdNumber_acc_y->display(acc_y);
00653 ui->lcdNumber_acc_z->display(acc_z);
00654 ui->lcdNumber_ang_x->display(ang_x);
00655 ui->lcdNumber_ang_y->display(ang_y);
00656 ui->lcdNumber_any_z->display(ang_z);
00657 ui->lcdNumber_mag_x->display(mag_x);
00658 ui->lcdNumber_mag_y->display(mag_y);
00659 ui->lcdNumber_mag_z->display(mag_z);
00660 }
00661
00662 void MainWindow::showLRFlines()
00663 {
00664 QString string1 = "No Lines";
00665 QString string2 = "Show Lines";
00666
00667 if(LRF_lines_show == false)
00668 {
00669 ui->ShowLRFlines->setText(string1);
00670 LRF_lines_show = true;
00671 hokuyo.showlines = true;
00672 }
00673 else
00674 {
00675 LRF_lines_show = false;
00676 ui->ShowLRFlines->setText(string2);
00677 hokuyo.showlines = false;
00678 }
00679
00680 }
00681
00682 void MainWindow::showIRdata(int value)
00683 {
00684
00685 if(value != 0)
00686 {
00687 hokuyo.showIR = true;
00688 hokuyo.showLRF = false;
00689 ui->showLRF->setEnabled(false);
00690 }
00691
00692 else
00693 {
00694 hokuyo.showIR = false;
00695
00696 ui->showLRF->setEnabled(true);
00697 }
00698
00699 }
00700
00701 void MainWindow::showLRFdata(int value)
00702 {
00703 if(value != 0)
00704 {
00705 hokuyo.showIR = false;
00706 hokuyo.showLRF = true;
00707 ui->ShowIRdata->setEnabled(false);
00708 }
00709
00710 else
00711 {
00712
00713 hokuyo.showLRF = false;
00714 ui->ShowIRdata->setEnabled(true);
00715 }
00716
00717
00718 }