diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 29ef7eba25..8d86f90e75 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1310,8 +1310,3 @@ bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode) } return rover.set_mode(*new_mode, MODE_REASON_GCS_COMMAND); } - -const AP_FWVersion &GCS_MAVLINK_Rover::get_fwver() const -{ - return rover.fwver; -} diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 0a7cf603ce..a278be061c 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -20,7 +20,6 @@ protected: AP_Camera *get_camera() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_VisualOdom *get_visual_odom() const override; - const AP_FWVersion &get_fwver() const override; uint8_t sysid_my_gcs() const override; diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index e81cb73896..382b5da6c8 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -28,7 +28,7 @@ Rover::Rover(void) : channel_throttle(nullptr), channel_aux(nullptr), channel_lateral(nullptr), - DataFlash{fwver.fw_string, g.log_bitmask}, + DataFlash{g.log_bitmask}, modes(&g.mode1), nav_controller(&L1_controller), control_mode(&mode_initializing), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index b5f323802b..5d260bb062 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -126,7 +126,6 @@ public: void loop(void) override; private: - static const AP_FWVersion fwver; // must be the first AP_Param variable declared to ensure its // constructor runs before the constructors of the other AP_Param diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 6e4955942b..b56bd5ffed 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -24,7 +24,7 @@ void Rover::init_ardupilot() hal.console->printf("\n\nInit %s" "\n\nFree RAM: %u\n", - fwver.fw_string, + AP::fwversion().fw_string, (unsigned)hal.util->available_memory()); // @@ -80,7 +80,7 @@ void Rover::init_ardupilot() // setup frsky telemetry #if FRSKY_TELEM_ENABLED == ENABLED - frsky_telemetry.init(serial_manager, fwver.fw_string, (is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER)); + frsky_telemetry.init(serial_manager, (is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER)); #endif #if DEVO_TELEM_ENABLED == ENABLED devo_telemetry.init(serial_manager); diff --git a/APMrover2/version.cpp b/APMrover2/version.cpp index 9f6c7a2ce0..147c3de7af 100644 --- a/APMrover2/version.cpp +++ b/APMrover2/version.cpp @@ -21,7 +21,7 @@ #include -const AP_FWVersion Rover::fwver{ +const AP_FWVersion AP_FWVersion::fwver{ .major = FW_MAJOR, .minor = FW_MINOR, .patch = FW_PATCH, @@ -33,9 +33,16 @@ const AP_FWVersion Rover::fwver{ .fw_hash_str = GIT_VERSION, #endif #ifdef PX4_GIT_VERSION + .middleware_name = "PX4", .middleware_hash_str = PX4_GIT_VERSION, #endif #ifdef NUTTX_GIT_VERSION + .os_name = "NuttX", .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 };