connectstartstopbar.cpp 28.7 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
//    Copyright (C) 2017, ETH Zurich, D-ITET, Paul Beuchat
//
//    This file is part of D-FaLL-System.
//
//    D-FaLL-System is free software: you can redistribute it and/or modify
//    it under the terms of the GNU General Public License as published by
//    the Free Software Foundation, either version 3 of the License, or
//    (at your option) any later version.
//
//    D-FaLL-System is distributed in the hope that it will be useful,
//    but WITHOUT ANY WARRANTY; without even the implied warranty of
//    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
//    GNU General Public License for more details.
//
//    You should have received a copy of the GNU General Public License
//    along with D-FaLL-System.  If not, see <http://www.gnu.org/licenses/>.
//
//
//    ----------------------------------------------------------------------------------
//    DDDD        FFFFF        L     L           SSSS  Y   Y   SSSS  TTTTT  EEEEE  M   M
//    D   D       F      aaa   L     L          S       Y Y   S        T    E      MM MM
//    D   D  ---  FFFF  a   a  L     L     ---   SSS     Y     SSS     T    EEE    M M M
//    D   D       F     a  aa  L     L              S    Y        S    T    E      M   M
//    DDDD        F      aa a  LLLL  LLLL       SSSS     Y    SSSS     T    EEEEE  M   M
//
//
//    DESCRIPTION:
//    The bar of the GUI for (dis-)connecting (from)to the Crazyradio
//    and for sending the {take-off,land,motors-off} commands
//
//    ----------------------------------------------------------------------------------





37
38
39
#include "connectstartstopbar.h"
#include "ui_connectstartstopbar.h"

40
41
42
43




44
45
46
47
48
49
ConnectStartStopBar::ConnectStartStopBar(QWidget *parent) :
    QWidget(parent),
    ui(new Ui::ConnectStartStopBar)
{
    ui->setupUi(this);

50

51
52
#ifdef CATKIN_MAKE
    // Get the namespace of this node
53
54
    std::string base_namespace = ros::this_node::getNamespace();
    ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] ros::this_node::getNamespace() =  " << base_namespace);
55
56
57
58
59
60
61
62
63
64
65


    // Get the type and ID of this parameter service
    bool isValid_type_and_ID = getTypeAndIDParameters();

    // Stall if the TYPE and ID are not valid
    if ( !isValid_type_and_ID )
    {
        ROS_ERROR("[CONNECT START STOP GUI BAR] Node NOT FUNCTIONING :-)");
        ros::spin();
    }
66
67
68
69
#else
    // Default as a coordinator when compiling with QtCreator
    m_type = TYPE_COORDINATOR;
    m_ID = 1;
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
#endif

    // SET THE INITIAL VALUE OF THE PRIVATE VARIABLES FOR THIS CLASS
    // > For keeping track of the current battery state
    m_battery_state = BATTERY_STATE_NORMAL;
    // > For keeping track of which image is currently displayed
    m_battery_status_label_image_current_index = -999;


    // SET THE STARTING RADIO STATUS TO BE: DISCONNECTED
    setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);

    // SET THE STARTING BATTERY VOLTAGE TO BE: UNKNOWN
    setBatteryVoltageText(-1.0f);

    // SET THE STARTING BATTERY LEVEL TO BE: UNAVAILABLE
    setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);

    // SET THE STARTING FLYING STATE STATUS TO BE: MOTORS OFF
89
    setFlyingState(STATE_UNAVAILABLE);
90
91
92
93
94
95

    // ENSURE THE F:YING STATE BUTTONS ARE AVAILABLE FOR A COORDINATOR
    if (m_type == TYPE_COORDINATOR)
    {
        enableFlyingStateButtons();
    }
96
97
98



99
100
#ifdef CATKIN_MAKE
    // CREATE A NODE HANDLE TO THE BASE NAMESPACE
101
    ros::NodeHandle base_nodeHandle(base_namespace);
102

103
    // CREATE A NODE HANDLE TO THE ROOT OF THE D-FaLL SYSTEM
104
    //ros::NodeHandle dfall_root_nodeHandle("/dfall");
105

106
    // SUBSCRIBERS AND PUBLISHERS:
107

108
    // > For Crazyradio commands based on button clicks
109
    crazyRadioCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/crazyRadioCommand", 1);
110
111

    // > For Flying state commands based on button clicks
112
    flyingStateCommandPublisher = base_nodeHandle.advertise<dfall_pkg::IntWithHeader>("FlyingAgentClient/Command", 1);
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128

    if (m_type == TYPE_AGENT)
    {
        // > For updating the "rf_status_label" picture
        crazyRadioStatusSubscriber = base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &ConnectStartStopBar::crazyRadioStatusCallback, this);

        // > For updating the current battery voltage
        batteryVoltageSubscriber = base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &ConnectStartStopBar::batteryVoltageCallback, this);
    
        // > For updating the current battery state
        //batteryStateSubscriber = base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &ConnectStartStopBar::batteryStateChangedCallback, this);

        // > For updating the current battery level
        batteryLevelSubscriber = base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &ConnectStartStopBar::batteryLevelCallback, this);
    
        // > For updating the "flying_state_label" picture
129
        flyingStateSubscriber = base_nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
130
131
132
133
134
    }
#endif

    // FURTHER INITILIASATIONS NEED TO OCCUR AFTER THE ROS RELATED
    // INITIALISATIONS ARE COMPLETE
135
136
137
    //if (m_type == TYPE_AGENT)
    //{
        // The loading of the "Context" is handled by the "topbanner"
138
        //loadCrazyflieContext();
139
    //}
140
141
142
143
144
145
146
147
148
149
150

    // ADD KEYBOARD SHORTCUTS
    // > For "all motors off", press the space bar
    ui->motors_off_button->setShortcut(tr("Space"));
}

ConnectStartStopBar::~ConnectStartStopBar()
{
    delete ui;
}

151
152
153
154
155


// > For making the "enable flight" and "disable flight" buttons unavailable
void ConnectStartStopBar::disableFlyingStateButtons()
{
156
157
158
    ui->motors_off_button->setEnabled(true);
    ui->enable_flying_button->setEnabled(false);
    ui->disable_flying_button->setEnabled(false);
159
160
161
162
163
}

// > For making the "enable flight" and "disable flight" buttons available
void ConnectStartStopBar::enableFlyingStateButtons()
{
164
165
166
    ui->motors_off_button->setEnabled(true);
    ui->enable_flying_button->setEnabled(true);
    ui->disable_flying_button->setEnabled(true);
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
}




//    ----------------------------------------------------------------------------------
//     CCCC  RRRR     A    ZZZZZ  Y   Y  RRRR     A    DDDD   III   OOO
//    C      R   R   A A      Z    Y Y   R   R   A A   D   D   I   O   O
//    C      RRRR   A   A    Z      Y    RRRR   A   A  D   D   I   O   O
//    C      R   R  AAAAA   Z       Y    R   R  AAAAA  D   D   I   O   O
//     CCCC  R   R  A   A  ZZZZZ    Y    R   R  A   A  DDDD   III   OOO
//    ----------------------------------------------------------------------------------



#ifdef CATKIN_MAKE
// PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES

// > For the Battery Voltage
void ConnectStartStopBar::crazyRadioStatusCallback(const std_msgs::Int32& msg)
{
    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Crazy Radio Status Callback called for agentID = " << m_agentID);
    setCrazyRadioStatus( msg.data );
}
#endif


// PRIVATE METHODS FOR SETTING PROPERTIES

void ConnectStartStopBar::setCrazyRadioStatus(int new_radio_status)
{
    // add more things whenever the status is changed
    switch(new_radio_status)
    {
        case CRAZY_RADIO_STATE_CONNECTED:
        {
            // SET THE APPROPRIATE IMAGE FOR THE RADIOSTATUS LABEL
            //m_rf_status_label_mutex.lock();
            //ui->rf_status_label->clear();
            QPixmap rf_connected_pixmap(":/images/rf_connected.png");
            ui->rf_status_label->setPixmap(rf_connected_pixmap);
            ui->rf_status_label->setScaledContents(true);
            //ui->rf_status_label->update();
            //m_rf_status_label_mutex.unlock();

            // ENABLE THE REMAINDER OF THE GUI
            if (m_type == TYPE_AGENT)
            {
                enableFlyingStateButtons();
            }
            break;
        }

        case CRAZY_RADIO_STATE_CONNECTING:
        {
            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
            //m_rf_status_label_mutex.lock();
            //ui->rf_status_label->clear();
            QPixmap rf_connecting_pixmap(":/images/rf_connecting.png");
            ui->rf_status_label->setPixmap(rf_connecting_pixmap);
            ui->rf_status_label->setScaledContents(true);
            //ui->rf_status_label->update();
            //m_rf_status_label_mutex.unlock();
            break;
        }

        case CRAZY_RADIO_STATE_DISCONNECTED:
        {
            // SET THE APPROPRIATE IMAGE FOR THE RADIO STATUS LABEL
            //m_rf_status_label_mutex.lock();
            //ui->rf_status_label->clear();
            QPixmap rf_disconnected_pixmap(":/images/rf_disconnected.png");
            ui->rf_status_label->setPixmap(rf_disconnected_pixmap);
            ui->rf_status_label->setScaledContents(true);
            //ui->rf_status_label->update();
            //m_rf_status_label_mutex.unlock();

            // DISABLE THE REMAINDER OF THE GUI
            if (m_type == TYPE_AGENT)
            {
                disableFlyingStateButtons();
            }
            break;
        }

        default:
        {
            break;
        }
    }
}





//    ----------------------------------------------------------------------------------
//    BBBB     A    TTTTT  TTTTT  EEEEE  RRRR   Y   Y
//    B   B   A A     T      T    E      R   R   Y Y
//    BBBB   A   A    T      T    EEE    RRRR     Y
//    B   B  AAAAA    T      T    E      R   R    Y
//    BBBB   A   A    T      T    EEEEE  R   R    Y
//    ----------------------------------------------------------------------------------



#ifdef CATKIN_MAKE
// PRIVATE CALLBACKS IN RESPONSE TO ROS MESSAGES

// > For the Battery Voltage
void ConnectStartStopBar::batteryVoltageCallback(const std_msgs::Float32& msg)
{
    //setBatteryVoltageTextAndImage( msg.data );
    setBatteryVoltageText( msg.data );
}


void ConnectStartStopBar::batteryStateChangedCallback(const std_msgs::Int32& msg)
{
    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Battery State Changed Callback called for agentID = " << m_agentID);
    setBatteryState( msg.data );
}


void ConnectStartStopBar::batteryLevelCallback(const std_msgs::Int32& msg)
{
    setBatteryImageBasedOnLevel( msg.data );
}
#endif



// PRIVATE METHODS FOR SETTING PROPERTIES

// > For updating the battery state
void ConnectStartStopBar::setBatteryState(int new_battery_state)
{
    // SET THE CLASS VARIABLE FOR TRACKING THE BATTERY STATE
    m_battery_state = new_battery_state;
}



// > For updating the battery voltage shown in the UI elements of "battery_voltage_lineEdit"
void ConnectStartStopBar::setBatteryVoltageText(float battery_voltage)
{
    // Lock the mutex
    //m_battery_voltage_lineEdit_mutex.lock();
    // Construct the text string
    QString qstr = "";
    if (battery_voltage >= 0.0f)
    {
        qstr.append(QString::number(battery_voltage, 'f', 2));
    }
    else
    {
        qstr.append("-.--");
    }
    qstr.append(" V");
    // Set the text to the battery voltage line edit
    ui->battery_voltage_lineEdit->setText(qstr);
    // Unlock the mutex
    //m_battery_voltage_lineEdit_mutex.unlock();
}



// > For updating the battery image shown in the UI element of "battery_status_label"
void ConnectStartStopBar::setBatteryImageBasedOnLevel(int battery_level)
{
    // COMPUTE THE BATTERY VOLTAGE AS A PERCENTAGE
    //float battery_voltage_percentage = fromVoltageToPercent(battery_voltage);

    // CONVERT THE VOLTAGE LEVEL TO AN INDEX OF WHICH BATTERY LEVEL IMAGE TO DISPLAY
    // > Initialise a local variable that will be set in the switch case below
    int new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
    // > Initialise a local variable for the string of which image to use
    QString qstr_new_image = "";
    qstr_new_image.append(":/images/");
    
    // Fill in these two local variables accordingly
    switch(battery_level)
    {
        case BATTERY_LEVEL_000:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_EMPTY;
            qstr_new_image.append("battery_empty.png");
            break;
        }
        case BATTERY_LEVEL_010:
        case BATTERY_LEVEL_020:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_20;
            qstr_new_image.append("battery_20.png");
            break;
        }
        case BATTERY_LEVEL_030:
        case BATTERY_LEVEL_040:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_40;
            qstr_new_image.append("battery_40.png");
            break;
        }
        case BATTERY_LEVEL_050:
        case BATTERY_LEVEL_060:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_60;
            qstr_new_image.append("battery_60.png");
            break;
        }
        case BATTERY_LEVEL_070:
        case BATTERY_LEVEL_080:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_80;
            qstr_new_image.append("battery_80.png");
            break;
        }
        case BATTERY_LEVEL_090:
        case BATTERY_LEVEL_100:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_FULL;
            qstr_new_image.append("battery_full.png");
            break;
        }
        case BATTERY_LEVEL_UNAVAILABLE:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNVAILABLE;
394
            qstr_new_image.append("battery_unavailable.png");
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
            break;
        }
        default:
        {
            new_image_index = BATTERY_LABEL_IMAGE_INDEX_UNKNOWN;
            qstr_new_image.append("battery_unknown.png");
            break;
        }
    }
    // UPDATE THE IMAGE DISPLAYED BASED ON THE "new index"
    // > Only if it is different from the current index
    m_battery_status_label_mutex.lock();
    if (m_battery_status_label_image_current_index != new_image_index)
    {
        // SET THE IMAGE FOR THE BATTERY STATUS LABEL
        ui->battery_status_label->clear();
        QPixmap battery_image_pixmap(qstr_new_image);
        ui->battery_status_label->setPixmap(battery_image_pixmap);
        ui->battery_status_label->setScaledContents(true);
        m_battery_status_label_image_current_index = new_image_index;
        ui->battery_status_label->update();
    }
    m_battery_status_label_mutex.unlock();
}





//    ----------------------------------------------------------------------------------
//    FFFFF  L      Y   Y  III   GGGG      SSSS  TTTTT    A    TTTTT  EEEE
//    F      L       Y Y    I   G         S        T     A A     T    E
//    FFF    L        Y     I   G          SSS     T    A   A    T    EEE
//    F      L        Y     I   G   G         S    T    AAAAA    T    E
//    F      LLLLL    Y    III   GGGG     SSSS     T    A   A    T    EEEEE
//    ----------------------------------------------------------------------------------



// RESPONDING TO CHANGES IN THE FLYING STATE
#ifdef CATKIN_MAKE
void ConnectStartStopBar::flyingStateChangedCallback(const std_msgs::Int32& msg)
{
    //ROS_INFO_STEAM("[COORDINATOR ROW GUI] Flying State Changed Callback called for agentID = " << m_agentID);
    setFlyingState(msg.data);
}
#endif

void ConnectStartStopBar::setFlyingState(int new_flying_state)
{
    // UPDATE THE LABEL TO DISPLAY THE FLYING STATE
    switch(new_flying_state)
    {
        case STATE_MOTORS_OFF:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_off_pixmap(":/images/flying_state_off.png");
            ui->flying_state_label->setPixmap(flying_state_off_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }

        case STATE_TAKE_OFF:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_enabling_pixmap(":/images/flying_state_enabling.png");
            ui->flying_state_label->setPixmap(flying_state_enabling_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }

        case STATE_FLYING:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_flying_pixmap(":/images/flying_state_flying.png");
            ui->flying_state_label->setPixmap(flying_state_flying_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }

        case STATE_LAND:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_disabling_pixmap(":/images/flying_state_disabling.png");
            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }

484
485
486
487
488
489
490
491
492
        case STATE_UNAVAILABLE:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_disabling_pixmap(":/images/flying_state_unavailable.png");
            ui->flying_state_label->setPixmap(flying_state_disabling_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }

493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
        default:
        {
            // SET THE APPROPRIATE IMAGE FOR THE FLYING STATE LABEL
            QPixmap flying_state_unknown_pixmap(":/images/flying_state_unknown.png");
            ui->flying_state_label->setPixmap(flying_state_unknown_pixmap);
            ui->flying_state_label->setScaledContents(true);
            break;
        }
    }
}





//    ----------------------------------------------------------------------------------
//    BBBB   U   U  TTTTT  TTTTT   OOO   N   N   SSSS
//    B   B  U   U    T      T    O   O  NN  N  S
//    BBBB   U   U    T      T    O   O  N N N   SSS
//    B   B  U   U    T      T    O   O  N  NN      S
//    BBBB    UUU     T      T     OOO   N   N  SSSS
//    ----------------------------------------------------------------------------------



void ConnectStartStopBar::on_rf_connect_button_clicked()
{
520
#ifdef CATKIN_MAKE
521
    dfall_pkg::IntWithHeader msg;
522
523
524
    fillIntMessageHeader(msg);
    msg.data = CMD_RECONNECT;
    this->crazyRadioCommandPublisher.publish(msg);
beuchatp's avatar
beuchatp committed
525
    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Connect button clicked");
526
#endif
527
528
}

529
530
void ConnectStartStopBar::on_rf_disconnect_button_clicked()
{
531
#ifdef CATKIN_MAKE
532
    dfall_pkg::IntWithHeader msg;
533
534
535
    fillIntMessageHeader(msg);
    msg.data = CMD_DISCONNECT;
    this->crazyRadioCommandPublisher.publish(msg);
beuchatp's avatar
beuchatp committed
536
    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Disconnect button clicked");
537
#endif
538
539
540
541
542
}

void ConnectStartStopBar::on_enable_flying_button_clicked()
{
#ifdef CATKIN_MAKE
543
    dfall_pkg::IntWithHeader msg;
544
545
546
    fillIntMessageHeader(msg);
    msg.data = CMD_CRAZYFLY_TAKE_OFF;
    this->flyingStateCommandPublisher.publish(msg);
beuchatp's avatar
beuchatp committed
547
    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Enable flying button clicked");
548
549
550
551
552
553
#endif
}

void ConnectStartStopBar::on_disable_flying_button_clicked()
{
#ifdef CATKIN_MAKE
554
    dfall_pkg::IntWithHeader msg;
555
556
557
    fillIntMessageHeader(msg);
    msg.data = CMD_CRAZYFLY_LAND;
    this->flyingStateCommandPublisher.publish(msg);
beuchatp's avatar
beuchatp committed
558
    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Disable flying button clicked");
559
560
561
562
563
564
#endif
}

void ConnectStartStopBar::on_motors_off_button_clicked()
{
#ifdef CATKIN_MAKE
565
    dfall_pkg::IntWithHeader msg;
566
567
568
    fillIntMessageHeader(msg);
    msg.data = CMD_CRAZYFLY_MOTORS_OFF;
    this->flyingStateCommandPublisher.publish(msg);
beuchatp's avatar
beuchatp committed
569
    ROS_INFO("[ENABLE CONTROLLER LOAD YAML GUI BAR] Motors-off button clicked");
570
571
572
573
574
575
#endif
}




576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
//    ----------------------------------------------------------------------------------
//      A     GGGG  EEEEE  N   N  TTTTT     III  DDDD    SSSS
//     A A   G      E      NN  N    T        I   D   D  S
//    A   A  G      EEE    N N N    T        I   D   D   SSS
//    AAAAA  G   G  E      N  NN    T        I   D   D      S
//    A   A   GGGG  EEEEE  N   N    T       III  DDDD   SSSS
//    ----------------------------------------------------------------------------------


void ConnectStartStopBar::setAgentIDsToCoordinate(QVector<int> agentIDs , bool shouldCoordinateAll)
{

    // Lock the mutex
    m_agentIDs_toCoordinate_mutex.lock();
    // Add the "coordinate all" flag
    m_shouldCoordinateAll = shouldCoordinateAll;
    // Clear the previous list of agent IDs
    m_vector_of_agentIDs_toCoordinate.clear();
    // Copy across the agent IDs, if necessary
    if (!shouldCoordinateAll)
    {
        for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
        {
            m_vector_of_agentIDs_toCoordinate.push_back( agentIDs[irow] );
        }
    }
    // Unlock the mutex
    m_agentIDs_toCoordinate_mutex.unlock();

605
606
607
608
609
610
611
612
613
614
615
616

#ifdef CATKIN_MAKE
    // If there is only one agent to coordinate,
    // then subscribe to the relevant data
    if (agentIDs.length() == 1)
    {

        // > Create the appropriate node handle
        QString agent_base_namespace = "/dfall/agent" + QString::number(agentIDs[0]).rightJustified(3, '0');
        ros::NodeHandle agent_base_nodeHandle(agent_base_namespace.toStdString());

        // > Request the current flying state
617
        ros::ServiceClient getCurrentFlyingStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("FlyingAgentClient/getCurrentFlyingState", false);
618
        dfall_pkg::IntIntService getFlyingStateCall;
619
620
621
622
623
624
625
626
627
628
629
630
        getFlyingStateCall.request.data = 0;
        getCurrentFlyingStateService.waitForExistence(ros::Duration(2.0));
        if(getCurrentFlyingStateService.call(getFlyingStateCall))
        {
            setFlyingState(getFlyingStateCall.response.data);
        }
        else
        {
            setFlyingState(STATE_UNAVAILABLE);
        }

        // > Request the current status of the crazy radio
631
632
        ros::ServiceClient getCurrentCrazyRadioStateService = agent_base_nodeHandle.serviceClient<dfall_pkg::IntIntService>("CrazyRadio/getCurrentCrazyRadioStatus", false);
        dfall_pkg::IntIntService getCrazyRadioCall;
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
        getCrazyRadioCall.request.data = 0;
        getCurrentCrazyRadioStateService.waitForExistence(ros::Duration(2.0));
        if(getCurrentCrazyRadioStateService.call(getCrazyRadioCall))
        {
            setCrazyRadioStatus(getCrazyRadioCall.response.data);
        }
        else
        {
            setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
        }

        // > For updating the "rf_status_label" picture
        crazyRadioStatusSubscriber = agent_base_nodeHandle.subscribe("CrazyRadio/CrazyRadioStatus", 1, &ConnectStartStopBar::crazyRadioStatusCallback, this);

        // > For updating the current battery voltage
        batteryVoltageSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/FilteredVoltage", 1, &ConnectStartStopBar::batteryVoltageCallback, this);

        // > For updating the current battery state
        //batteryStateSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/ChangedStateTo", 1, &ConnectStartStopBar::batteryStateChangedCallback, this);

        // > For updating the current battery level
        batteryLevelSubscriber = agent_base_nodeHandle.subscribe("BatteryMonitor/Level", 1, &ConnectStartStopBar::batteryLevelCallback, this);

        // > For updating the "flying_state_label" picture
657
        flyingStateSubscriber = agent_base_nodeHandle.subscribe("FlyingAgentClient/flyingState", 1, &ConnectStartStopBar::flyingStateChangedCallback, this);
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
    }
    else
    {
        // Unsubscribe
        crazyRadioStatusSubscriber.shutdown();
        batteryVoltageSubscriber.shutdown();
        //batteryStateSubscriber.shutdown();
        batteryLevelSubscriber.shutdown();
        flyingStateSubscriber.shutdown();

        // Set information back to the default
        setCrazyRadioStatus(CRAZY_RADIO_STATE_DISCONNECTED);
        setBatteryVoltageText(-1.0f);
        setBatteryImageBasedOnLevel(BATTERY_LEVEL_UNAVAILABLE);
        setFlyingState(STATE_UNAVAILABLE);

    }
#endif


678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
#ifdef CATKIN_MAKE
#else
    // TO ASSIST WITH DEBUGGING WHEN COMPILED AND RUN IN "QtCreator"
    QTextStream(stdout) << "[CONNECT START STOP GUI BAR] is coordinating agentIDs:";
    for ( int irow = 0 ; irow < agentIDs.length() ; irow++ )
    {
        QTextStream(stdout) << " " << agentIDs[irow];
    }
    QTextStream(stdout) << " " << endl;
#endif
}




693
694
695
696
697
698
699
700
701
702
703
704
705

//    ----------------------------------------------------------------------------------
//    M   M   SSSS   GGG      H   H  EEEEE    A    DDDD   EEEEE  RRRR
//    MM MM  S      G   G     H   H  E       A A   D   D  E      R   R
//    M M M   SSS   G         HHHHH  EEE    A   A  D   D  EEE    RRRR
//    M   M      S  G   G     H   H  E      AAAAA  D   D  E      R   R
//    M   M  SSSS    GGGG     H   H  EEEEE  A   A  DDDD   EEEEE  R   R
//    ----------------------------------------------------------------------------------



#ifdef CATKIN_MAKE
// Fill the head for a message
706
void ConnectStartStopBar::fillIntMessageHeader( dfall_pkg::IntWithHeader & msg )
707
708
709
710
711
712
713
714
715
716
{
    switch (m_type)
    {
        case TYPE_AGENT:
        {
            msg.shouldCheckForID = false;
            break;
        }
        case TYPE_COORDINATOR:
        {
717
718
719
720
721
722
723
            // Lock the mutex
            m_agentIDs_toCoordinate_mutex.lock();
            // Add the "coordinate all" flag
            msg.shouldCheckForID = !(m_shouldCoordinateAll);
            // Add the agent IDs if necessary
            if (!m_shouldCoordinateAll)
            {
724
                for ( int irow = 0 ; irow < m_vector_of_agentIDs_toCoordinate.size() ; irow++ )
725
726
727
728
729
730
                {
                    msg.agentIDs.push_back( m_vector_of_agentIDs_toCoordinate[irow] );
                }
            }
            // Unlock the mutex
            m_agentIDs_toCoordinate_mutex.unlock();
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
            break;
        }

        default:
        {
            msg.shouldCheckForID = true;
            ROS_ERROR("[ENABLE CONTROLLER LOAD YAML GUI BAR] The 'm_type' variable was not recognised.");
            break;
        }
    } 
}
#endif





//    ----------------------------------------------------------------------------------
//    III  DDDD       &&&      TTTTT  Y   Y  PPPP   EEEEE
//     I   D   D     &           T     Y Y   P   P  E
//     I   D   D      &          T      Y    PPPP   EEE
//     I   D   D     & & &       T      Y    P      E
//    III  DDDD       &&&        T      Y    P      EEEEE
//    ----------------------------------------------------------------------------------



#ifdef CATKIN_MAKE
bool ConnectStartStopBar::getTypeAndIDParameters()
{
    // Initialise the return variable as success
    bool return_was_successful = true;

    // Create a "ros::NodeHandle" type local variable "nodeHandle" as the current node,
    // the "~" indcates that "self" is the node handle assigned to this variable.
    ros::NodeHandle nodeHandle("~");

    // Get the value of the "type" parameter into a local string variable
    std::string type_string;
    if(!nodeHandle.getParam("type", type_string))
    {
        // Throw an error if the agent ID parameter could not be obtained
        ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get type");
    }

    // Set the "m_type" class variable based on this string loaded
    if ((!type_string.compare("coordinator")))
    {
        m_type = TYPE_COORDINATOR;
    }
    else if ((!type_string.compare("agent")))
    {
        m_type = TYPE_AGENT;
    }
    else
    {
        // Set "m_type" to the value indicating that it is invlid
        m_type = TYPE_INVALID;
        return_was_successful = false;
        ROS_ERROR("[CONNECT START STOP GUI BAR] The 'type' parameter retrieved was not recognised.");
    }


    // Construct the string to the namespace of this Paramater Service
    switch (m_type)
    {
        case TYPE_AGENT:
        {
            // Get the value of the "agentID" parameter into the class variable "m_Id"
            if(!nodeHandle.getParam("agentID", m_ID))
            {
                // Throw an error if the agent ID parameter could not be obtained
                return_was_successful = false;
                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get agentID");
            }
            else
            {
                // Inform the user about the type and ID
                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type AGENT with ID = " << m_ID);
            }
            break;
        }

        // A COORDINATOR TYPE PARAMETER SERVICE IS REQUESTED FROM:
        // > The master GUI
        case TYPE_COORDINATOR:
        {
            // Get the value of the "coordID" parameter into the class variable "m_Id"
            if(!nodeHandle.getParam("coordID", m_ID))
            {
                // Throw an error if the coord ID parameter could not be obtained
                return_was_successful = false;
                ROS_ERROR("[CONNECT START STOP GUI BAR] Failed to get coordID");
            }
            else
            {
                // Inform the user about the type and ID
                ROS_INFO_STREAM("[CONNECT START STOP GUI BAR] Is of type COORDINATOR with ID = " << m_ID);
            }
            break;
        }

        default:
        {
            // Throw an error if the type is not recognised
            return_was_successful = false;
            ROS_ERROR("[CONNECT START STOP GUI BAR] The 'm_type' variable was not recognised.");
            break;
        }
    }
841

842
843
    // Return
    return return_was_successful;
844
}
845
#endif