SendMavCommandTest.cc 5.41 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 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


#include "SendMavCommandTest.h"
#include "MultiVehicleManager.h"
#include "QGCApplication.h"

void SendMavCommandTest::_noFailure(void)
{
    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_1, true /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_1);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_ACCEPTED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

void SendMavCommandTest::_failureShowError(void)
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_2, true /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_2);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);

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

void SendMavCommandTest::_failureNoShowError(void)
{
    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_2, false /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_2);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

void SendMavCommandTest::_noFailureAfterRetry(void)
{
    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_3, true /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_3);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_ACCEPTED);
    QCOMPARE(arguments.at(4).toBool(), false);
}

void SendMavCommandTest::_failureAfterRetry(void)
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_4, true /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_4);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), false);

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

void SendMavCommandTest::_failureAfterNoReponse(void)
{
    // Will pop error about request failure
    setExpectedMessageBox(QMessageBox::Ok);

    _connectMockLink();

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

    vehicle->sendMavCommand(MAV_COMP_ID_ALL, MAV_CMD_USER_5, true /* showError */);

    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());
    QCOMPARE(arguments.at(2).toInt(), (int)MAV_CMD_USER_5);
    QCOMPARE(arguments.at(3).toInt(), (int)MAV_RESULT_FAILED);
    QCOMPARE(arguments.at(4).toBool(), true);

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