diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index a9ebbb8ab7..d769cfe35b 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -138,7 +138,7 @@ public: #if AP_AHRS_NAVEKF_AVAILABLE void send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optflow); #endif - void send_autopilot_version(void) const; + void send_autopilot_version(uint64_t capabilities = 0) const; void send_local_position(const AP_AHRS &ahrs) const; void send_vibration(const AP_InertialSensor &ins) const; void send_mission_item_reached(uint16_t seq) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 4571cea1cd..f60f217724 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1245,9 +1245,8 @@ void GCS_MAVLINK::send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optf /* send AUTOPILOT_VERSION packet */ -void GCS_MAVLINK::send_autopilot_version(void) const +void GCS_MAVLINK::send_autopilot_version(uint64_t capabilities) const { - uint16_t capabilities = 0; uint32_t flight_sw_version = 0; uint32_t middleware_sw_version = 0; uint32_t os_sw_version = 0;