GCS_MAVLink: use AP_FWVersion singleton

This commit is contained in:
Peter Barker 2018-06-13 20:29:52 +10:00 committed by Francisco Ferreira
parent 611dcb694b
commit c333a905df
4 changed files with 12 additions and 11 deletions

View File

@ -257,7 +257,6 @@ protected:
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }
virtual bool set_mode(uint8_t mode) = 0;
virtual const AP_FWVersion &get_fwver() const = 0;
void set_ekf_origin(const Location& loc);
virtual MAV_TYPE frame_type() const = 0;

View File

@ -1492,7 +1492,7 @@ void GCS_MAVLINK::send_autopilot_version() const
uint16_t product_id = 0;
uint64_t uid = 0;
uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0};
const AP_FWVersion &version = get_fwver();
const AP_FWVersion &version = AP::fwversion();
flight_sw_version = version.major << (8 * 3) | \
version.minor << (8 * 2) | \
@ -2422,12 +2422,17 @@ void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t *msg)
void GCS_MAVLINK::send_banner()
{
// mark the firmware version in the tlog
const AP_FWVersion &fwver = get_fwver();
const AP_FWVersion &fwver = AP::fwversion();
send_text(MAV_SEVERITY_INFO, fwver.fw_string);
if (fwver.middleware_hash_str && fwver.os_hash_str) {
send_text(MAV_SEVERITY_INFO, "PX4: %s NuttX: %s",
fwver.middleware_hash_str, fwver.os_hash_str);
if (fwver.middleware_name && fwver.os_name) {
send_text(MAV_SEVERITY_INFO, "%s: %s %s: %s",
fwver.middleware_name, fwver.middleware_hash_str,
fwver.os_name, fwver.os_hash_str);
} else if (fwver.os_name) {
send_text(MAV_SEVERITY_INFO, "%s: %s",
fwver.os_name, fwver.os_hash_str);
}
// send system ID if we can

View File

@ -1,6 +1,6 @@
#include "GCS.h"
const AP_FWVersion fwver
const AP_FWVersion AP_FWVersion::fwver
{
major: 3,
minor: 1,
@ -26,7 +26,6 @@ protected:
AP_Mission *get_mission() override { return nullptr; }
AP_Rally *get_rally() const override { return nullptr; };
AP_Camera *get_camera() const override { return nullptr; };
const AP_FWVersion &get_fwver() const override { return fwver; }
uint8_t sysid_my_gcs() const override { return 1; }
bool set_mode(uint8_t mode) override { return false; };

View File

@ -11,8 +11,7 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
const AP_FWVersion fwver
const AP_FWVersion AP_FWVersion::fwver
{
major: 3,
minor: 1,
@ -35,7 +34,6 @@ protected:
AP_Camera *get_camera() const override { return nullptr; };
uint8_t sysid_my_gcs() const override { return 1; }
bool set_mode(uint8_t mode) override { return false; };
const AP_FWVersion &get_fwver() const override { return fwver; }
// dummy information:
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }