PxQuadMAV.cc 2.83 KB
Newer Older
1 2 3 4 5 6
#include "PxQuadMAV.h"

PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) :
        UAS(mavlink, id)
{
}
7 8 9 10 11 12 13 14 15 16 17 18 19

/**
 * This function is called by MAVLink once a complete, uncorrupted (CRC check valid)
 * mavlink packet is received.
 *
 * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port).
 *             messages can be sent back to the system via this link
 * @param message MAVLink message, as received from the MAVLink protocol stack
 */
void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
    // Let UAS handle the default message set
    UAS::receiveMessage(link, message);
20
    mavlink_message_t* msg = &message;
21

22
        //qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
pixhawk's avatar
pixhawk committed
23 24


25
    // Handle your special messages
26
    switch (msg->msgid)
27
    {
28
    case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT:
29
        {
30 31 32 33
            mavlink_watchdog_heartbeat_t payload;
            mavlink_msg_watchdog_heartbeat_decode(msg, &payload);
            
            emit watchdogReceived(this->uasId, payload.watchdog_id, payload.process_count);
34
        }
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
        break;
        
    case MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO:
        {
            mavlink_watchdog_process_info_t payload;
            mavlink_msg_watchdog_process_info_decode(msg, &payload);
            
            emit processReceived(this->uasId, payload.watchdog_id, payload.process_id, QString((const char*)payload.name), QString((const char*)payload.arguments), payload.timeout);
        }
        break;
        
    case MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS:
        {
            mavlink_watchdog_process_status_t payload;
            mavlink_msg_watchdog_process_status_decode(msg, &payload);
            emit processChanged(this->uasId, payload.watchdog_id, payload.process_id, payload.state, (payload.muted == 1) ? true : false, payload.crashes, payload.pid);
        }
        break;
53 54 55 56 57 58 59 60 61
    case MAVLINK_MSG_ID_DEBUG_VECT:
        {
            mavlink_debug_vect_t vect;
            mavlink_msg_debug_vect_decode(msg, &vect);
            QString str((const char*)vect.name);
            emit valueChanged(uasId, str+".x", vect.x, MG::TIME::getGroundTimeNow());
            emit valueChanged(uasId, str+".y", vect.y, MG::TIME::getGroundTimeNow());
            emit valueChanged(uasId, str+".z", vect.z, MG::TIME::getGroundTimeNow());
        }
lm's avatar
lm committed
62
        break;
63 64 65 66 67
    default:
        // Do nothing
        break;
    }
}
68 69 70 71 72 73 74 75 76 77

void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command)
{
    mavlink_watchdog_command_t payload;
    payload.target_system_id = uasId;
    payload.watchdog_id = watchdogId;
    payload.process_id = processId;
    payload.command_id = (uint8_t)command;

    mavlink_message_t msg;
lm's avatar
lm committed
78
    mavlink_msg_watchdog_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &payload);
79 80
    sendMessage(msg);
}