Plane: use AP_FWVersion singleton

This commit is contained in:
Peter Barker 2018-06-13 21:12:16 +10:00 committed by Francisco Ferreira
parent 4168bd709c
commit 2b7f9247e8
6 changed files with 11 additions and 12 deletions

View File

@ -1709,8 +1709,3 @@ bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode)
} }
return false; return false;
} }
const AP_FWVersion &GCS_MAVLINK_Plane::get_fwver() const
{
return plane.fwver;
}

View File

@ -23,7 +23,6 @@ protected:
AP_Camera *get_camera() const override; AP_Camera *get_camera() const override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_Rally *get_rally() const override; AP_Rally *get_rally() const override;
const AP_FWVersion &get_fwver() const override;
uint8_t sysid_my_gcs() const override; uint8_t sysid_my_gcs() const override;

View File

@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Plane class constructor for main Plane class
*/ */
Plane::Plane(void) Plane::Plane(void)
: DataFlash(fwver.fw_string, g.log_bitmask) : DataFlash(g.log_bitmask)
{ {
// C++11 doesn't allow in-class initialisation of bitfields // C++11 doesn't allow in-class initialisation of bitfields
auto_state.takeoff_complete = true; auto_state.takeoff_complete = true;

View File

@ -158,7 +158,6 @@ public:
void loop() override; void loop() override;
private: private:
static const AP_FWVersion fwver;
// key aircraft parameters passed to multiple libraries // key aircraft parameters passed to multiple libraries
AP_Vehicle::FixedWing aparm; AP_Vehicle::FixedWing aparm;

View File

@ -24,7 +24,7 @@ void Plane::init_ardupilot()
hal.console->printf("\n\nInit %s" hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n", "\n\nFree RAM: %u\n",
fwver.fw_string, AP::fwversion().fw_string,
(unsigned)hal.util->available_memory()); (unsigned)hal.util->available_memory());
@ -116,8 +116,7 @@ void Plane::init_ardupilot()
// setup frsky // setup frsky
#if FRSKY_TELEM_ENABLED == ENABLED #if FRSKY_TELEM_ENABLED == ENABLED
// setup frsky, and pass a number of parameters to the library // setup frsky, and pass a number of parameters to the library
frsky_telemetry.init(serial_manager, fwver.fw_string, frsky_telemetry.init(serial_manager, MAV_TYPE_FIXED_WING);
MAV_TYPE_FIXED_WING);
#endif #endif
#if DEVO_TELEM_ENABLED == ENABLED #if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.init(serial_manager); devo_telemetry.init(serial_manager);

View File

@ -21,7 +21,7 @@
#include <AP_Common/AP_FWVersion.h> #include <AP_Common/AP_FWVersion.h>
const AP_FWVersion Plane::fwver{ const AP_FWVersion AP_FWVersion::fwver{
.major = FW_MAJOR, .major = FW_MAJOR,
.minor = FW_MINOR, .minor = FW_MINOR,
.patch = FW_PATCH, .patch = FW_PATCH,
@ -33,9 +33,16 @@ const AP_FWVersion Plane::fwver{
.fw_hash_str = GIT_VERSION, .fw_hash_str = GIT_VERSION,
#endif #endif
#ifdef PX4_GIT_VERSION #ifdef PX4_GIT_VERSION
.middleware_name = "PX4",
.middleware_hash_str = PX4_GIT_VERSION, .middleware_hash_str = PX4_GIT_VERSION,
#endif #endif
#ifdef NUTTX_GIT_VERSION #ifdef NUTTX_GIT_VERSION
.os_name = "NuttX",
.os_hash_str = NUTTX_GIT_VERSION, .os_hash_str = NUTTX_GIT_VERSION,
#elif defined(CHIBIOS_GIT_VERSION)
.middleware_name = nullptr,
.middleware_hash_str = nullptr,
.os_name = "ChibiOS",
.os_hash_str = CHIBIOS_GIT_VERSION,
#endif #endif
}; };