@ -233,7 +233,15 @@ Vehicle::Vehicle(LinkInterface* link,
@@ -233,7 +233,15 @@ Vehicle::Vehicle(LinkInterface* link,
connect ( _mav , SIGNAL ( attitudeChanged ( UASInterface * , double , double , double , quint64 ) ) , this , SLOT ( _updateAttitude ( UASInterface * , double , double , double , quint64 ) ) ) ;
connect ( _mav , SIGNAL ( attitudeChanged ( UASInterface * , int , double , double , double , quint64 ) ) , this , SLOT ( _updateAttitude ( UASInterface * , int , double , double , double , quint64 ) ) ) ;
if ( _highLatencyLink ) {
// High latency links don't request information
_setMaxProtoVersion ( 100 ) ;
_setCapabilities ( 0 ) ;
_initialPlanRequestComplete = true ;
_missionManagerInitialRequestSent = true ;
_geoFenceManagerInitialRequestSent = true ;
_rallyPointManagerInitialRequestSent = true ;
} else {
// Ask the vehicle for protocol version info.
sendMavCommand ( MAV_COMP_ID_ALL , // Don't know default component id yet.
MAV_CMD_REQUEST_PROTOCOL_VERSION ,
@ -245,6 +253,7 @@ Vehicle::Vehicle(LinkInterface* link,
@@ -245,6 +253,7 @@ Vehicle::Vehicle(LinkInterface* link,
MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES ,
false , // No error shown if fails
1 ) ; // Request firmware version
}
_firmwarePlugin - > initializeVehicle ( this ) ;
@ -684,6 +693,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -684,6 +693,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_ADSB_VEHICLE :
_handleADSBVehicle ( message ) ;
break ;
case MAVLINK_MSG_ID_HIGH_LATENCY2 :
_handleHighLatency2 ( message ) ;
break ;
case MAVLINK_MSG_ID_SERIAL_CONTROL :
{
@ -797,6 +809,47 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
@@ -797,6 +809,47 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
emit coordinateChanged ( _coordinate ) ;
}
void Vehicle : : _handleHighLatency2 ( mavlink_message_t & message )
{
mavlink_high_latency2_t highLatency2 ;
mavlink_msg_high_latency2_decode ( & message , & highLatency2 ) ;
#if 0
typedef struct __mavlink_high_latency2_t {
uint16_t wp_num ; /*< Current waypoint number*/
uint16_t failure_flags ; /*< Indicates failures as defined in MAV_FAILURE_FLAG ENUM. */
uint8_t flight_mode ; /*< Flight Mode of the vehicle as defined in the FLIGHT_MODE ENUM*/
uint8_t failsafe ; /*< Indicates if a failsafe mode is triggered, defined in MAV_FAILSAFE_FLAG ENUM*/
} ) mavlink_high_latency2_t ;
# endif
// FIXME: flight mode not yet supported
_coordinate . setLatitude ( highLatency2 . latitude / ( double ) 1E7 ) ;
_coordinate . setLongitude ( highLatency2 . longitude / ( double ) 1E7 ) ;
_coordinate . setAltitude ( highLatency2 . altitude ) ;
emit coordinateChanged ( _coordinate ) ;
_airSpeedFact . setRawValue ( ( double ) highLatency2 . airspeed / 5.0 ) ;
_groundSpeedFact . setRawValue ( ( double ) highLatency2 . groundspeed / 5.0 ) ;
_climbRateFact . setRawValue ( ( double ) highLatency2 . climb_rate / 10.0 ) ;
_headingFact . setRawValue ( ( double ) highLatency2 . heading * 2.0 ) ;
_windFactGroup . direction ( ) - > setRawValue ( ( double ) highLatency2 . wind_heading * 2.0 ) ;
_windFactGroup . speed ( ) - > setRawValue ( ( double ) highLatency2 . windspeed / 5.0 ) ;
_batteryFactGroup . percentRemaining ( ) - > setRawValue ( highLatency2 . battery ) ;
_temperatureFactGroup . temperature1 ( ) - > setRawValue ( highLatency2 . temperature_air ) ;
_gpsFactGroup . lat ( ) - > setRawValue ( highLatency2 . latitude * 1e-7 ) ;
_gpsFactGroup . lon ( ) - > setRawValue ( highLatency2 . longitude * 1e-7 ) ;
_gpsFactGroup . count ( ) - > setRawValue ( 0 ) ;
_gpsFactGroup . hdop ( ) - > setRawValue ( highLatency2 . eph = = UINT8_MAX ? std : : numeric_limits < double > : : quiet_NaN ( ) : highLatency2 . eph / 10.0 ) ;
_gpsFactGroup . vdop ( ) - > setRawValue ( highLatency2 . epv = = UINT8_MAX ? std : : numeric_limits < double > : : quiet_NaN ( ) : highLatency2 . epv / 10.0 ) ;
}
void Vehicle : : _handleAltitude ( mavlink_message_t & message )
{
mavlink_altitude_t altitude ;
@ -1351,6 +1404,7 @@ void Vehicle::_addLink(LinkInterface* link)
@@ -1351,6 +1404,7 @@ void Vehicle::_addLink(LinkInterface* link)
qCDebug ( VehicleLog ) < < " _addLink: " < < QString ( " %1 " ) . arg ( ( ulong ) link , 0 , 16 ) ;
_links + = link ;
_updatePriorityLink ( ) ;
_updateHighLatencyLink ( ) ;
connect ( _toolbox - > linkManager ( ) , & LinkManager : : linkInactive , this , & Vehicle : : _linkInactiveOrDeleted ) ;
connect ( _toolbox - > linkManager ( ) , & LinkManager : : linkDeleted , this , & Vehicle : : _linkInactiveOrDeleted ) ;
connect ( link , & LinkInterface : : highLatencyChanged , this , & Vehicle : : _updateHighLatencyLink ) ;