#include "QGXPX4UAS.h"QGXPX4UAS::QGXPX4UAS(MAVLinkProtocol*mavlink,QThread*thread,intid):UAS(mavlink,thread,id){}/** * 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 */voidQGXPX4UAS::receiveMessage(LinkInterface*link,mavlink_message_tmessage){UAS::receiveMessage(link,message);}voidQGXPX4UAS::processParamValueMsgHook(mavlink_message_t&msg,constQString¶mName,constmavlink_param_value_t&rawValue,mavlink_param_union_t¶mValue){intcompId=msg.compid;if(paramName=="SYS_AUTOSTART"){boolok;intval=parameters.value(compId)->value(paramName).toInt(&ok);if(ok&&val==0){emitmisconfigurationDetected(this);qDebug()<<"HINTING MISCONFIGURATION";}qDebug()<<"SYS_AUTOSTART FOUND WITH VAL: "<<val;}}