SendMavCommandWithSignallingTest.cc 6.7 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


11
#include "SendMavCommandWithSignallingTest.h"
12 13
#include "MultiVehicleManager.h"
#include "QGCApplication.h"
14
#include "MockLink.h"
15

16
void SendMavCommandWithSignallingTest::_noFailure(void)
17
{
18
    _connectMockLinkNoInitialConnectSequence();
19

20 21 22
    MultiVehicleManager*    vehicleMgr  = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle*                vehicle     = vehicleMgr->activeVehicle();
    QSignalSpy              spyResult(vehicle, &Vehicle::mavCommandResult);
23

24
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED, true /* showError */);
25 26 27 28 29

    QCOMPARE(spyResult.wait(10000), true);
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
30
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED);
31 32 33 34
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_ACCEPTED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

35
void SendMavCommandWithSignallingTest::_failureShowError(void)
36 37 38 39
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

40
    _connectMockLinkNoInitialConnectSequence();
41 42 43 44 45

    MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle* vehicle = vehicleMgr->activeVehicle();
    QVERIFY(vehicle);

46
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED, true /* showError */);
47 48 49 50 51 52

    QSignalSpy spyResult(vehicle, SIGNAL(mavCommandResult(int, int, int, int, bool)));
    QCOMPARE(spyResult.wait(10000), true);
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
53
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED);
54 55 56 57 58 59 60
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);

    // User should have been notified
    checkExpectedMessageBox();
}

61
void SendMavCommandWithSignallingTest::_failureNoShowError(void)
62
{
63
    _connectMockLinkNoInitialConnectSequence();
64 65 66 67 68

    MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle* vehicle = vehicleMgr->activeVehicle();
    QVERIFY(vehicle);

69
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED, false /* showError */);
70 71 72 73 74 75

    QSignalSpy spyResult(vehicle, SIGNAL(mavCommandResult(int, int, int, int, bool)));
    QCOMPARE(spyResult.wait(10000), true);
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
76
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_FAILED);
77 78 79 80
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

81
void SendMavCommandWithSignallingTest::_noFailureAfterRetry(void)
82
{
83
    _connectMockLinkNoInitialConnectSequence();
84 85 86 87 88

    MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle* vehicle = vehicleMgr->activeVehicle();
    QVERIFY(vehicle);

89
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED, true /* showError */);
90 91 92 93 94 95

    QSignalSpy spyResult(vehicle, SIGNAL(mavCommandResult(int, int, int, int, bool)));
    QCOMPARE(spyResult.wait(10000), true);
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
96
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_ACCEPTED);
97 98 99 100
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_ACCEPTED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

101
void SendMavCommandWithSignallingTest::_failureAfterRetry(void)
102 103 104 105
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

106
    _connectMockLinkNoInitialConnectSequence();
107 108 109 110 111

    MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle* vehicle = vehicleMgr->activeVehicle();
    QVERIFY(vehicle);

112
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED, true /* showError */);
113 114 115 116 117 118

    QSignalSpy spyResult(vehicle, SIGNAL(mavCommandResult(int, int, int, int, bool)));
    QCOMPARE(spyResult.wait(10000), true);
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
119
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_SECOND_ATTEMPT_RESULT_FAILED);
120 121 122 123 124 125 126
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);

    // User should have been notified
    checkExpectedMessageBox();
}

127
void SendMavCommandWithSignallingTest::_failureAfterNoReponse(void)
128 129 130 131
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

132
    _connectMockLinkNoInitialConnectSequence();
133 134 135 136 137

    MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle* vehicle = vehicleMgr->activeVehicle();
    QVERIFY(vehicle);

138
    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, true /* showError */);
139 140

    QSignalSpy spyResult(vehicle, SIGNAL(mavCommandResult(int, int, int, int, bool)));
Don Gagne's avatar
Don Gagne committed
141
    QCOMPARE(spyResult.wait(20000), true);
142 143 144
    QList<QVariant> arguments = spyResult.takeFirst();
    QCOMPARE(arguments.count(), 5);
    QCOMPARE(arguments.at(0).toInt(), vehicle->id());
145
    QCOMPARE(arguments.at(2).toInt(), (int)MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE);
146 147 148 149 150 151
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), true);

    // User should have been notified
    checkExpectedMessageBox();
}
152 153 154 155 156 157 158 159 160 161 162 163 164 165 166

void SendMavCommandWithSignallingTest::_unexpectedAck(void)
{
    _connectMockLinkNoInitialConnectSequence();

    MultiVehicleManager*    vehicleMgr  = qgcApp()->toolbox()->multiVehicleManager();
    Vehicle*                vehicle     = vehicleMgr->activeVehicle();
    QSignalSpy              spyResult(vehicle, &Vehicle::mavCommandResult);

    _mockLink->sendUnexpectedCommandAck(MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED, MAV_RESULT_ACCEPTED);
    QCOMPARE(spyResult.wait(100), false);

    _mockLink->sendUnexpectedCommandAck(MockLink::MAV_CMD_MOCKLINK_ALWAYS_RESULT_ACCEPTED, MAV_RESULT_FAILED);
    QCOMPARE(spyResult.wait(100), false);
}