QGCUASFileManager.cc 18.3 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
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL 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.
 
 QGROUNDCONTROL 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 QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

24 25
#include "QGCUASFileManager.h"
#include "QGC.h"
Lorenz Meier's avatar
Lorenz Meier committed
26 27 28 29
#include "MAVLinkProtocol.h"

#include <QFile>
#include <QDir>
none's avatar
none committed
30
#include <string>
Lorenz Meier's avatar
Lorenz Meier committed
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

static const quint32 crctab[] =
{
    0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
    0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
    0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
    0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
    0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
    0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
    0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
    0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
    0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
    0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
    0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
    0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
    0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
    0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
    0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
    0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
    0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
    0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
    0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
    0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
    0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
    0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
    0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
    0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
    0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
    0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
    0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
    0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
    0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
    0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
    0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
    0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};
67

68

69 70
QGCUASFileManager::QGCUASFileManager(QObject* parent, UASInterface* uas) :
    QObject(parent),
71
    _currentOperation(kCOIdle),
Lorenz Meier's avatar
Lorenz Meier committed
72
    _mav(uas),
73 74
    _encdata_seq(0),
    _activeSession(0)
Lorenz Meier's avatar
Lorenz Meier committed
75
{
76 77
    bool connected = connect(&_ackTimer, SIGNAL(timeout()), this, SLOT(_ackTimeout()));
    Q_ASSERT(connected);
78
    Q_UNUSED(connected);    // Silence retail unused variable error
Lorenz Meier's avatar
Lorenz Meier committed
79 80
}

81 82 83 84 85
/// @brief Calculates a 32 bit CRC for the specified request.
///     @param request Request to calculate CRC for. request->size must be set correctly.
///     @param state previous crc state
/// @return Calculated CRC
quint32 QGCUASFileManager::crc32(Request* request, unsigned state)
86
{
87 88 89 90 91 92 93 94 95 96 97 98
    uint8_t* data = (uint8_t*)request;
    size_t cbData = sizeof(RequestHeader) + request->hdr.size;
    
    // Always calculate CRC with 0 initial CRC value
    quint32 crcSave = request->hdr.crc32;
    request->hdr.crc32 = 0;
    
    for (size_t i=0; i < cbData; i++)
        state = crctab[(state ^ data[i]) & 0xff] ^ (state >> 8);
    
    request->hdr.crc32 = crcSave;

Lorenz Meier's avatar
Lorenz Meier committed
99
    return state;
100 101
}

102 103
/// @brief Respond to the Ack associated with the Open command with the next Read command.
void QGCUASFileManager::_openAckResponse(Request* openAck)
104 105 106
{
    _currentOperation = kCORead;
    _activeSession = openAck->hdr.session;
107 108 109
    
    _readOffset = 0;                // Start reading at beginning of file
    _readFileAccumulator.clear();   // Start with an empty file
110 111 112 113 114 115 116 117 118 119 120
    
    Request request;
    request.hdr.magic = 'f';
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdRead;
    request.hdr.offset = _readOffset;
    request.hdr.size = sizeof(request.data);
    
    _sendRequest(&request);
}

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
/// @brief Closes out a read session by writing the file and doing cleanup.
///     @param success true: successful download completion, false: error during download
void QGCUASFileManager::_closeReadSession(bool success)
{
    if (success) {
        QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
        
        QFile file(downloadFilePath);
        if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
            _emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
            return;
        }
        
        qint64 bytesWritten = file.write((const char *)_readFileAccumulator, _readFileAccumulator.length());
        if (bytesWritten != _readFileAccumulator.length()) {
            file.close();
            _emitErrorMessage(tr("Unable to write data to local file (%1)").arg(downloadFilePath));
            return;
        }
        file.close();
        
        _emitStatusMessage(tr("Download complete '%1'").arg(downloadFilePath));
    }
    
    // Close the open session
    _sendTerminateCommand();
}

149
/// @brief Respond to the Ack associated with the Read command.
150
void QGCUASFileManager::_readAckResponse(Request* readAck)
151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167
{
    if (readAck->hdr.session != _activeSession) {
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
        _emitErrorMessage(tr("Read: Incorrect session returned"));
        return;
    }
    
    if (readAck->hdr.offset != _readOffset) {
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
        _emitErrorMessage(tr("Read: Offset returned (%1) differs from offset requested (%2)").arg(readAck->hdr.offset).arg(_readOffset));
        return;
    }

    _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
    
168 169
    if (readAck->hdr.size == sizeof(readAck->data)) {
        // Possibly still more data to read, send next read request
170
        
171 172
        _currentOperation = kCORead;
        
173
        _readOffset += readAck->hdr.size;
174 175 176 177 178 179 180 181 182
        
        Request request;
        request.hdr.magic = 'f';
        request.hdr.session = _activeSession;
        request.hdr.opcode = kCmdRead;
        request.hdr.offset = _readOffset;
        
        _sendRequest(&request);
    } else {
183
        // We only receieved a partial buffer back. These means we are at EOF
184
        _currentOperation = kCOIdle;
185
        _closeReadSession(true /* success */);
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
    }
}

/// @brief Respond to the Ack associated with the List command.
void QGCUASFileManager::_listAckResponse(Request* listAck)
{
    if (listAck->hdr.offset != _listOffset) {
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset));
        return;
    }
    
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
    
    // parse filenames out of the buffer
    while (offset < cBytes) {
        const char * ptr = ((const char *)listAck->data) + offset;
        
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
        size_t nlen = strnlen(ptr, cBytesLeft);
        if (nlen < 2) {
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr));
            return;
        } else if (nlen == cBytesLeft) {
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Missing NULL termination in list entry"));
            return;
        }
218

Don Gagne's avatar
Don Gagne committed
219
        // Returned names are prepended with D for directory, F for file, U for unknown
220 221
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
Don Gagne's avatar
Don Gagne committed
222
            _emitStatusMessage(ptr);
223 224
        }
    
225 226 227 228 229 230
        // account for the name + NUL
        offset += nlen + 1;
        
        cListEntries++;
    }

231 232 233 234
    if (listAck->hdr.size == 0) {
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == kRspAck);
        _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
235
        emit listComplete();
236 237
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
238 239 240
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
241 242 243
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
244 245
void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
246
    Q_UNUSED(link);
247
    
none's avatar
none committed
248 249 250 251
    if (message.msgid != MAVLINK_MSG_ID_ENCAPSULATED_DATA) {
        // wtf, not for us
        return;
    }
252
    
253 254
    _clearAckTimeout();

none's avatar
none committed
255 256
    mavlink_encapsulated_data_t data;
    mavlink_msg_encapsulated_data_decode(&message, &data);
257
    Request* request = (Request*)&data.data[0];
258

259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
    // FIXME: Check CRC
    
    if (request->hdr.opcode == kRspAck) {
        
        switch (_currentOperation) {
            case kCOIdle:
                // we should not be seeing anything here.. shut the other guy up
                _sendCmdReset();
                break;
                
            case kCOAck:
                // We are expecting an ack back
                _currentOperation = kCOIdle;
                break;
                
            case kCOList:
275
                _listAckResponse(request);
276
                break;
277 278
            
            case kCOOpen:
279
                _openAckResponse(request);
280
                break;
281
                
282
            case kCORead:
283
                _readAckResponse(request);
284 285
                break;

286 287 288 289 290
            default:
                _emitErrorMessage("Ack received in unexpected state");
                break;
        }
    } else if (request->hdr.opcode == kRspNak) {
291 292 293 294 295
        Q_ASSERT(request->hdr.size == 1); // Should only have one byte of error code
        
        OperationState previousOperation = _currentOperation;
        uint8_t errorCode = request->data[0];
        
296
        _currentOperation = kCOIdle;
297 298 299
        
        if (previousOperation == kCOList && errorCode == kErrEOF) {
            // This is not an error, just the end of the read loop
Don Gagne's avatar
Don Gagne committed
300
            emit listComplete();
301 302 303 304 305 306 307 308 309 310 311 312 313
            return;
        } else if (previousOperation == kCORead && errorCode == kErrEOF) {
            // This is not an error, just the end of the read loop
            _closeReadSession(true /* success */);
            return;
        } else {
            // Generic Nak handling
            if (previousOperation == kCORead) {
                // Nak error during read loop, download failed
                _closeReadSession(false /* failure */);
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
314 315 316
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
317
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
318 319 320
    }
}

321
void QGCUASFileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
322
{
323 324 325
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
326 327
    }

328 329
    // clear the text widget
    emit resetStatusMessages();
none's avatar
none committed
330 331

    // initialise the lister
332
    _listPath = dirPath;
333 334
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
335 336

    // and send the initial request
337
    _sendListCommand();
none's avatar
none committed
338 339
}

340 341 342 343 344 345
void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& str)
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
    request->hdr.size = strnlen((const char *)&request->data[0], sizeof(request->data));
}

346
void QGCUASFileManager::_sendListCommand(void)
none's avatar
none committed
347
{
348
    Request request;
none's avatar
none committed
349

350 351 352 353 354
    request.hdr.magic = 'f';
    request.hdr.session = 0;
    request.hdr.opcode = kCmdList;
    request.hdr.offset = _listOffset;
    
355
    _fillRequestWithString(&request, _listPath);
356 357
    
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
358 359
}

360 361 362 363
/// @brief Downloads the specified file.
///     @param from File to download from UAS, fully qualified path
///     @param downloadDir Local directory to download file to
void QGCUASFileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
364
{
365 366 367
    if (from.isEmpty()) {
        return;
    }
Don Gagne's avatar
Don Gagne committed
368
    
369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384
    _readFileDownloadDir.setPath(downloadDir.absolutePath());
    
    // We need to strip off the file name from the fully qualified path. We can't use the usual QDir
    // routines because this path does not exist locally.
    int i;
    for (i=from.size()-1; i>=0; i--) {
        if (from[i] == '/') {
            break;
        }
    }
    i++; // move past slash
    _readFileDownloadFilename = from.right(from.size() - i);
    
    emit resetStatusMessages();
    
    _currentOperation = kCOOpen;
Lorenz Meier's avatar
Lorenz Meier committed
385

386 387 388 389 390 391 392
    Request request;
    request.hdr.magic = 'f';
    request.hdr.session = 0;
    request.hdr.opcode = kCmdOpen;
    request.hdr.offset = 0;
    _fillRequestWithString(&request, from);
    _sendRequest(&request);
393
}
none's avatar
none committed
394 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

QString QGCUASFileManager::errorString(uint8_t errorCode)
{
    switch(errorCode) {
    case kErrNone:
        return QString("no error");
    case kErrNoRequest:
        return QString("bad request");
    case kErrNoSession:
        return QString("bad session");
    case kErrSequence:
        return QString("bad sequence number");
    case kErrNotDir:
        return QString("not a directory");
    case kErrNotFile:
        return QString("not a file");
    case kErrEOF:
        return QString("read beyond end of file");
    case kErrNotAppend:
        return QString("write not at end of file");
    case kErrTooBig:
        return QString("file too big");
    case kErrIO:
        return QString("device I/O error");
    case kErrPerm:
        return QString("permission denied");
420 421 422 423
    case kErrUnknownCommand:
        return QString("unknown command");
    case kErrCrc:
        return QString("bad crc");
none's avatar
none committed
424
    default:
425
        return QString("unknown error code");
none's avatar
none committed
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

/// @brief Sends a command which only requires an opcode and no additional data
///     @param opcode Opcode to send
///     @param newOpState State to put state machine into
/// @return TRUE: command sent, FALSE: command not sent, waiting for previous command to finish
bool QGCUASFileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
    
    Request request;
    request.hdr.magic = 'f';
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
    
    _currentOperation = newOpState;
    
    _sendRequest(&request);
    
    return TRUE;
}

/// @brief Starts the ack timeout timer
void QGCUASFileManager::_setupAckTimeout(void)
{
    Q_ASSERT(!_ackTimer.isActive());
    
    _ackTimer.setSingleShot(true);
    _ackTimer.start(_ackTimerTimeoutMsecs);
}

/// @brief Clears the ack timeout timer
void QGCUASFileManager::_clearAckTimeout(void)
{
    Q_ASSERT(_ackTimer.isActive());
    
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
void QGCUASFileManager::_ackTimeout(void)
{
Don Gagne's avatar
Don Gagne committed
474 475 476
    // Make sure to set _currentOperation state before emitting error message. Code may respond
    // to error message signal by sending another command, which will fail if state is not back
    // to idle. FileView UI works this way with the List command.
477 478 479 480

    switch (_currentOperation) {
        case kCORead:
            _currentOperation = kCOAck;
Don Gagne's avatar
Don Gagne committed
481
            _emitErrorMessage(tr("Timeout waiting for ack: Sending Terminate command"));
482 483 484 485
            _sendTerminateCommand();
            break;
        default:
            _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
486
            _emitErrorMessage(tr("Timeout waiting for ack"));
487 488 489 490 491 492 493 494 495 496 497
            break;
    }
}

void QGCUASFileManager::_sendTerminateCommand(void)
{
    Request request;
    request.hdr.magic = 'f';
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdTerminate;
    _sendRequest(&request);
498 499 500 501
}

void QGCUASFileManager::_emitErrorMessage(const QString& msg)
{
502
    qDebug() << "QGCUASFileManager: Error" << msg;
503 504 505
    emit errorMessage(msg);
}

506 507 508 509 510 511
void QGCUASFileManager::_emitStatusMessage(const QString& msg)
{
    qDebug() << "QGCUASFileManager: Status" << msg;
    emit statusMessage(msg);
}

512 513 514 515 516 517 518 519 520 521 522
/// @brief Sends the specified Request out to the UAS.
void QGCUASFileManager::_sendRequest(Request* request)
{
    mavlink_message_t message;
    
    _setupAckTimeout();

    request->hdr.crc32 = crc32(request);
    // FIXME: Send correct system id instead of harcoded 250
    mavlink_msg_encapsulated_data_pack(250, 0, &message, _encdata_seq, (uint8_t*)request);
    _mav->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
523
}