GCS_MAVLink: make arguments mandatory for send_autopilot_version

This commit is contained in:
squilter 2015-08-21 10:49:01 -07:00 committed by Grant Morphett
parent 74edf9cb1e
commit 705d3d567a
2 changed files with 2 additions and 2 deletions

View File

@ -148,7 +148,7 @@ public:
#if AP_AHRS_NAVEKF_AVAILABLE
void send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optflow);
#endif
void send_autopilot_version(uint8_t major_version = 0, uint8_t minor_version = 0, uint8_t patch_version = 0, enum FIRMWARE_VERSION_TYPE version_type = FIRMWARE_VERSION_TYPE_DEV) const;
void send_autopilot_version(uint8_t major_version, uint8_t minor_version, uint8_t patch_version, uint8_t version_type) const;
void send_local_position(const AP_AHRS &ahrs) const;
void send_vibration(const AP_InertialSensor &ins) const;

View File

@ -1262,7 +1262,7 @@ void GCS_MAVLINK::send_opticalflow(AP_AHRS_NavEKF &ahrs, const OpticalFlow &optf
/*
send AUTOPILOT_VERSION packet
*/
void GCS_MAVLINK::send_autopilot_version(uint8_t major_version, uint8_t minor_version, uint8_t patch_version, enum FIRMWARE_VERSION_TYPE version_type) const
void GCS_MAVLINK::send_autopilot_version(uint8_t major_version, uint8_t minor_version, uint8_t patch_version, uint8_t version_type) const
{
uint32_t flight_sw_version = 0;
uint32_t middleware_sw_version = 0;