@ -20,93 +20,123 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
@@ -20,93 +20,123 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
UAS : : receiveMessage ( link , message ) ;
mavlink_message_t * msg = & message ;
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
# ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Handle your special messages
switch ( msg - > msgid )
if ( message . sysid = = uasId )
{
case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT :
QString uasState ;
QString stateDescription ;
QString patternPath ;
switch ( message . msgid )
{
mavlink_watchdog_heartbeat_t payload ;
mavlink_msg_watchdog_heartbeat_decode ( msg , & payload ) ;
emit watchdogReceived ( this - > uasId , payload . watchdog_id , payload . process_count ) ;
}
break ;
case MAVLINK_MSG_ID_RAW_AUX :
{
mavlink_raw_aux_t raw ;
mavlink_msg_raw_aux_decode ( & message , & raw ) ;
quint64 time = getUnixTime ( 0 ) ;
emit valueChanged ( uasId , " Pressure " , raw . baro , time ) ;
emit valueChanged ( uasId , " Temperature " , raw . temp , time ) ;
}
break ;
case MAVLINK_MSG_ID_PATTERN_DETECTED :
{
QByteArray b ;
b . resize ( 256 ) ;
mavlink_msg_pattern_detected_get_file ( & message , ( int8_t * ) b . data ( ) ) ;
b . append ( ' \0 ' ) ;
QString path = QString ( b ) ;
bool detected ( mavlink_msg_pattern_detected_get_detected ( & message ) = = 1 ? true : false ) ;
emit detectionReceived ( uasId , path , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , mavlink_msg_pattern_detected_get_confidence ( & message ) , detected ) ;
}
break ;
case MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT :
{
mavlink_watchdog_heartbeat_t payload ;
mavlink_msg_watchdog_heartbeat_decode ( msg , & payload ) ;
emit watchdogReceived ( this - > uasId , payload . watchdog_id , payload . process_count ) ;
}
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 ;
{
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 ;
{
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 ;
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 ( ) ) ;
}
break ;
{
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 ( ) ) ;
}
break ;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE :
{
mavlink_vision_position_estimate_t pos ;
mavlink_msg_vision_position_estimate_decode ( & message , & pos ) ;
quint64 time = getUnixTime ( pos . usec ) ;
emit valueChanged ( uasId , " vis. time " , pos . usec , time ) ;
emit valueChanged ( uasId , " vis. roll " , pos . roll , time ) ;
emit valueChanged ( uasId , " vis. pitch " , pos . pitch , time ) ;
emit valueChanged ( uasId , " vis. yaw " , pos . yaw , time ) ;
emit valueChanged ( uasId , " vis. x " , pos . x , time ) ;
emit valueChanged ( uasId , " vis. y " , pos . y , time ) ;
emit valueChanged ( uasId , " vis. z " , pos . z , time ) ;
emit valueChanged ( uasId , " vis. vx " , pos . vx , time ) ;
emit valueChanged ( uasId , " vis. vy " , pos . vy , time ) ;
emit valueChanged ( uasId , " vis. vz " , pos . vz , time ) ;
emit valueChanged ( uasId , " vis. vyaw " , pos . vyaw , time ) ;
// Set internal state
if ( ! positionLock )
{
// If position was not locked before, notify positive
GAudioOutput : : instance ( ) - > notifyPositive ( ) ;
mavlink_vision_position_estimate_t pos ;
mavlink_msg_vision_position_estimate_decode ( & message , & pos ) ;
quint64 time = getUnixTime ( pos . usec ) ;
emit valueChanged ( uasId , " vis. time " , pos . usec , time ) ;
emit valueChanged ( uasId , " vis. roll " , pos . roll , time ) ;
emit valueChanged ( uasId , " vis. pitch " , pos . pitch , time ) ;
emit valueChanged ( uasId , " vis. yaw " , pos . yaw , time ) ;
emit valueChanged ( uasId , " vis. x " , pos . x , time ) ;
emit valueChanged ( uasId , " vis. y " , pos . y , time ) ;
emit valueChanged ( uasId , " vis. z " , pos . z , time ) ;
emit valueChanged ( uasId , " vis. vx " , pos . vx , time ) ;
emit valueChanged ( uasId , " vis. vy " , pos . vy , time ) ;
emit valueChanged ( uasId , " vis. vz " , pos . vz , time ) ;
emit valueChanged ( uasId , " vis. vyaw " , pos . vyaw , time ) ;
// Set internal state
if ( ! positionLock )
{
// If position was not locked before, notify positive
GAudioOutput : : instance ( ) - > notifyPositive ( ) ;
}
positionLock = true ;
}
positionLock = true ;
}
break ;
break ;
case MAVLINK_MSG_ID_AUX_STATUS :
{
mavlink_aux_status_t status ;
mavlink_msg_aux_status_decode ( & message , & status ) ;
emit loadChanged ( this , status . load / 10.0f ) ;
emit errCountChanged ( uasId , " IMU " , " I2C0 " , status . i2c0_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " I2C1 " , status . i2c1_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " SPI0 " , status . spi0_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " SPI1 " , status . spi1_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " UART " , status . uart_total_err_count ) ;
emit valueChanged ( this , " Load " , ( ( float ) status . load ) / 1000.0f , MG : : TIME : : getGroundTimeNow ( ) ) ;
}
break ;
{
mavlink_aux_status_t status ;
mavlink_msg_aux_status_decode ( & message , & status ) ;
emit loadChanged ( this , status . load / 10.0f ) ;
emit errCountChanged ( uasId , " IMU " , " I2C0 " , status . i2c0_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " I2C1 " , status . i2c1_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " SPI0 " , status . spi0_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " SPI1 " , status . spi1_err_count ) ;
emit errCountChanged ( uasId , " IMU " , " UART " , status . uart_total_err_count ) ;
emit valueChanged ( this , " Load " , ( ( float ) status . load ) / 1000.0f , MG : : TIME : : getGroundTimeNow ( ) ) ;
}
break ;
default :
// Do nothing
break ;
// Do nothing
break ;
}
}
# endif
}
void PxQuadMAV : : sendProcessCommand ( int watchdogId , int processId , unsigned int command )
{
# ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_watchdog_command_t payload ;
payload . target_system_id = uasId ;
payload . watchdog_id = watchdogId ;
@ -116,4 +146,5 @@ void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int c
@@ -116,4 +146,5 @@ void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int c
mavlink_message_t msg ;
mavlink_msg_watchdog_command_encode ( mavlink - > getSystemId ( ) , mavlink - > getComponentId ( ) , & msg , & payload ) ;
sendMessage ( msg ) ;
# endif
}