ESP8266ComponentController.cc 15.3 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

dogmaphobic's avatar
dogmaphobic committed
10 11 12 13 14 15 16 17 18

/// @file
///     @brief  ESP8266 WiFi Config Qml Controller
///     @author Gus Grubba <mavlink@grubba.com>

#include "ESP8266ComponentController.h"
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include "UAS.h"
19
#include "ParameterManager.h"
dogmaphobic's avatar
dogmaphobic committed
20

21
#include <QHostAddress>
22
#include <QtEndian>
23

dogmaphobic's avatar
dogmaphobic committed
24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41
QGC_LOGGING_CATEGORY(ESP8266ComponentControllerLog, "ESP8266ComponentControllerLog")

#define MAX_RETRIES 5

//-----------------------------------------------------------------------------
ESP8266ComponentController::ESP8266ComponentController()
    : _waitType(WAIT_FOR_NOTHING)
    , _retries(0)
{
    for(int i = 1; i < 12; i++) {
        _channels.append(QString::number(i));
    }
    _baudRates.append("57600");
    _baudRates.append("115200");
    _baudRates.append("230400");
    _baudRates.append("460800");
    _baudRates.append("921600");
    connect(&_timer, &QTimer::timeout, this, &ESP8266ComponentController::_processTimeout);
42
    connect(_vehicle, &Vehicle::commandLongAck, this, &ESP8266ComponentController::_commandAck);
dogmaphobic's avatar
dogmaphobic committed
43 44 45 46 47 48
    Fact* ssid = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID4");
    connect(ssid, &Fact::valueChanged, this, &ESP8266ComponentController::_ssidChanged);
    Fact* paswd = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD4");
    connect(paswd, &Fact::valueChanged, this, &ESP8266ComponentController::_passwordChanged);
    Fact* baud = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "UART_BAUDRATE");
    connect(baud, &Fact::valueChanged, this, &ESP8266ComponentController::_baudChanged);
49 50
    Fact* ver = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "SW_VER");
    connect(ver, &Fact::valueChanged, this, &ESP8266ComponentController::_versionChanged);
dogmaphobic's avatar
dogmaphobic committed
51 52 53 54 55 56 57 58
}

//-----------------------------------------------------------------------------
ESP8266ComponentController::~ESP8266ComponentController()
{

}

59 60 61 62 63 64 65 66 67
//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::version()
{
    uint32_t uv = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")->rawValue().toUInt();
    QString versionString = QString("%1.%2.%3").arg(uv >> 24).arg((uv >> 16) & 0xFF).arg(uv & 0xFFFF);
    return versionString;
}

dogmaphobic's avatar
dogmaphobic committed
68 69 70 71 72 73
//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::wifiIPAddress()
{
    if(_ipAddress.isEmpty()) {
        if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_IPADDRESS")) {
74
            QHostAddress address(qFromBigEndian(getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_IPADDRESS")->rawValue().toUInt()));
dogmaphobic's avatar
dogmaphobic committed
75 76 77 78 79 80 81 82
            _ipAddress = address.toString();
        } else {
            _ipAddress = "192.168.4.1";
        }
    }
    return _ipAddress;
}

dogmaphobic's avatar
dogmaphobic committed
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 152 153 154 155 156 157 158 159 160
//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::wifiSSID()
{
    uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID1")->rawValue().toUInt();
    uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID2")->rawValue().toUInt();
    uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID3")->rawValue().toUInt();
    uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID4")->rawValue().toUInt();
    char tmp[20];
    memcpy(&tmp[0],  &s1, sizeof(uint32_t));
    memcpy(&tmp[4],  &s2, sizeof(uint32_t));
    memcpy(&tmp[8],  &s3, sizeof(uint32_t));
    memcpy(&tmp[12], &s4, sizeof(uint32_t));
    return QString(tmp);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::setWifiSSID(QString ssid)
{
    char tmp[20];
    memset(tmp, 0, sizeof(tmp));
    std::string	sid = ssid.toStdString();
    strncpy(tmp, sid.c_str(), sizeof(tmp));
    Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID1");
    Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID2");
    Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID3");
    Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSID4");
    uint32_t u;
    memcpy(&u, &tmp[0], sizeof(uint32_t));
    f1->setRawValue(QVariant(u));
    memcpy(&u, &tmp[4], sizeof(uint32_t));
    f2->setRawValue(QVariant(u));
    memcpy(&u, &tmp[8], sizeof(uint32_t));
    f3->setRawValue(QVariant(u));
    memcpy(&u, &tmp[12], sizeof(uint32_t));
    f4->setRawValue(QVariant(u));
}

//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::wifiPassword()
{
    uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD1")->rawValue().toUInt();
    uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD2")->rawValue().toUInt();
    uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD3")->rawValue().toUInt();
    uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD4")->rawValue().toUInt();
    char tmp[20];
    memcpy(&tmp[0],  &s1, sizeof(uint32_t));
    memcpy(&tmp[4],  &s2, sizeof(uint32_t));
    memcpy(&tmp[8],  &s3, sizeof(uint32_t));
    memcpy(&tmp[12], &s4, sizeof(uint32_t));
    return QString(tmp);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::setWifiPassword(QString password)
{
    char tmp[20];
    memset(tmp, 0, sizeof(tmp));
    std::string	pwd = password.toStdString();
    strncpy(tmp, pwd.c_str(), sizeof(tmp));
    Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD1");
    Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD2");
    Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD3");
    Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PASSWORD4");
    uint32_t u;
    memcpy(&u, &tmp[0], sizeof(uint32_t));
    f1->setRawValue(QVariant(u));
    memcpy(&u, &tmp[4], sizeof(uint32_t));
    f2->setRawValue(QVariant(u));
    memcpy(&u, &tmp[8], sizeof(uint32_t));
    f3->setRawValue(QVariant(u));
    memcpy(&u, &tmp[12], sizeof(uint32_t));
    f4->setRawValue(QVariant(u));
}

161 162 163 164 165 166 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
//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::wifiSSIDSta()
{
    if(!parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1")) {
        return QString();
    }
    uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1")->rawValue().toUInt();
    uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA2")->rawValue().toUInt();
    uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA3")->rawValue().toUInt();
    uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA4")->rawValue().toUInt();
    char tmp[20];
    memcpy(&tmp[0],  &s1, sizeof(uint32_t));
    memcpy(&tmp[4],  &s2, sizeof(uint32_t));
    memcpy(&tmp[8],  &s3, sizeof(uint32_t));
    memcpy(&tmp[12], &s4, sizeof(uint32_t));
    return QString(tmp);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::setWifiSSIDSta(QString ssid)
{
    if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1")) {
        char tmp[20];
        memset(tmp, 0, sizeof(tmp));
        std::string	sid = ssid.toStdString();
        strncpy(tmp, sid.c_str(), sizeof(tmp));
        Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA1");
        Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA2");
        Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA3");
        Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_SSIDSTA4");
        uint32_t u;
        memcpy(&u, &tmp[0], sizeof(uint32_t));
        f1->setRawValue(QVariant(u));
        memcpy(&u, &tmp[4], sizeof(uint32_t));
        f2->setRawValue(QVariant(u));
        memcpy(&u, &tmp[8], sizeof(uint32_t));
        f3->setRawValue(QVariant(u));
        memcpy(&u, &tmp[12], sizeof(uint32_t));
        f4->setRawValue(QVariant(u));
    }
}

//-----------------------------------------------------------------------------
QString
ESP8266ComponentController::wifiPasswordSta()
{
    if(!parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA1")) {
        return QString();
    }
    uint32_t s1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA1")->rawValue().toUInt();
    uint32_t s2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA2")->rawValue().toUInt();
    uint32_t s3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA3")->rawValue().toUInt();
    uint32_t s4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA4")->rawValue().toUInt();
    char tmp[20];
    memcpy(&tmp[0],  &s1, sizeof(uint32_t));
    memcpy(&tmp[4],  &s2, sizeof(uint32_t));
    memcpy(&tmp[8],  &s3, sizeof(uint32_t));
    memcpy(&tmp[12], &s4, sizeof(uint32_t));
    return QString(tmp);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::setWifiPasswordSta(QString password)
{
    if(parameterExists(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA1")) {
        char tmp[20];
        memset(tmp, 0, sizeof(tmp));
        std::string	pwd = password.toStdString();
        strncpy(tmp, pwd.c_str(), sizeof(tmp));
        Fact* f1 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA1");
        Fact* f2 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA2");
        Fact* f3 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA3");
        Fact* f4 = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "WIFI_PWDSTA4");
        uint32_t u;
        memcpy(&u, &tmp[0], sizeof(uint32_t));
        f1->setRawValue(QVariant(u));
        memcpy(&u, &tmp[4], sizeof(uint32_t));
        f2->setRawValue(QVariant(u));
        memcpy(&u, &tmp[8], sizeof(uint32_t));
        f3->setRawValue(QVariant(u));
        memcpy(&u, &tmp[12], sizeof(uint32_t));
        f4->setRawValue(QVariant(u));
    }
}

dogmaphobic's avatar
dogmaphobic committed
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
//-----------------------------------------------------------------------------
int
ESP8266ComponentController::baudIndex()
{
    int b = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "UART_BAUDRATE")->rawValue().toInt();
    switch (b) {
        case 57600:
            return 0;
        case 115200:
            return 1;
        case 230400:
            return 2;
        case 460800:
            return 3;
        case 921600:
        default:
            return 4;
    }
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::setBaudIndex(int idx)
{
    if(idx >= 0 && idx != baudIndex()) {
        int baud = 921600;
        switch(idx) {
            case 0:
                baud = 57600;
                break;
            case 1:
                baud = 115200;
                break;
            case 2:
                baud = 230400;
                break;
            case 3:
                baud = 460800;
                break;
            default:
                baud = 921600;
        }
        Fact* b = getParameterFact(MAV_COMP_ID_UDP_BRIDGE, "UART_BAUDRATE");
        b->setRawValue(baud);
    }
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::reboot()
{
    _waitType = WAIT_FOR_REBOOT;
    emit busyChanged();
    _retries  = MAX_RETRIES;
    _reboot();
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::restoreDefaults()
{
    _waitType = WAIT_FOR_RESTORE;
    emit busyChanged();
    _retries  = MAX_RETRIES;
    _restoreDefaults();
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_reboot()
{
    mavlink_message_t msg;
321 322

    mavlink_msg_command_long_pack_chan(
dogmaphobic's avatar
dogmaphobic committed
323 324
        qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
        qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
325
        _vehicle->priorityLink()->mavlinkChannel(),
dogmaphobic's avatar
dogmaphobic committed
326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343
        &msg,
        _vehicle->id(),
        MAV_COMP_ID_UDP_BRIDGE,
        MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
        1.0f, // Confirmation
        0.0f, // Param1
        1.0f, // Param2
        0.0f,0.0f,0.0f,0.0f,0.0f);
    qCDebug(ESP8266ComponentControllerLog) << "_reboot()";
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    _timer.start(1000);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_restoreDefaults()
{
    mavlink_message_t msg;
344
    mavlink_msg_command_long_pack_chan(
dogmaphobic's avatar
dogmaphobic committed
345 346
        qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
        qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
347
        _vehicle->priorityLink()->mavlinkChannel(),
dogmaphobic's avatar
dogmaphobic committed
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
        &msg,
        _vehicle->id(),
        MAV_COMP_ID_UDP_BRIDGE,
        MAV_CMD_PREFLIGHT_STORAGE,
        1.0f, // Confirmation
        2.0f, // Param1
        0.0f,0.0f,0.0f,0.0f,0.0f,0.0f);
    qCDebug(ESP8266ComponentControllerLog) << "_restoreDefaults()";
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    _timer.start(1000);
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_processTimeout()
{
    if(!--_retries) {
        qCDebug(ESP8266ComponentControllerLog) << "_processTimeout Giving Up";
        _timer.stop();
        _waitType = WAIT_FOR_NOTHING;
        emit busyChanged();
    } else {
        switch(_waitType) {
            case WAIT_FOR_REBOOT:
                qCDebug(ESP8266ComponentControllerLog) << "_processTimeout for Reboot";
                _reboot();
                break;
            case WAIT_FOR_RESTORE:
                qCDebug(ESP8266ComponentControllerLog) << "_processTimeout for Restore Defaults";
                _restoreDefaults();
                break;
        }
    }
}

//-----------------------------------------------------------------------------
void
385
ESP8266ComponentController::_commandAck(uint8_t compID, uint16_t command, uint8_t result)
dogmaphobic's avatar
dogmaphobic committed
386 387 388 389 390 391 392 393 394 395 396 397 398 399
{
    if(compID == MAV_COMP_ID_UDP_BRIDGE) {
        if(result != MAV_RESULT_ACCEPTED) {
            qWarning() << "ESP8266ComponentController command" << command << "rejected.";
            return;
        }
        if((_waitType == WAIT_FOR_REBOOT  && command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) ||
           (_waitType == WAIT_FOR_RESTORE && command == MAV_CMD_PREFLIGHT_STORAGE))
        {
            _timer.stop();
            _waitType = WAIT_FOR_NOTHING;
            emit busyChanged();
            qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command;
            if(command == MAV_CMD_PREFLIGHT_STORAGE) {
400
                _vehicle->parameterManager()->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE);
dogmaphobic's avatar
dogmaphobic committed
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
            }
        }
    }
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_ssidChanged(QVariant)
{
    emit wifiSSIDChanged();
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_passwordChanged(QVariant)
{
    emit wifiPasswordChanged();
}

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_baudChanged(QVariant)
{
    emit baudIndexChanged();
}
426 427 428 429 430 431 432

//-----------------------------------------------------------------------------
void
ESP8266ComponentController::_versionChanged(QVariant)
{
    emit versionChanged();
}