Sub: use AP_FWVersion singleton

This commit is contained in:
Peter Barker 2018-06-13 20:27:47 +10:00 committed by Francisco Ferreira
parent 1a1ae54e07
commit c17514cf85
5 changed files with 10 additions and 9 deletions

View File

@ -1369,11 +1369,6 @@ bool GCS_MAVLINK_Sub::set_mode(uint8_t mode)
return sub.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
const AP_FWVersion &GCS_MAVLINK_Sub::get_fwver() const
{
return sub.fwver;
}
int32_t GCS_MAVLINK_Sub::global_position_int_alt() const {
if (!sub.ap.depth_sensor_present) {
return 0;

View File

@ -16,7 +16,6 @@ protected:
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
AP_Camera *get_camera() const override;
const AP_FWVersion &get_fwver() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;

View File

@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Sub class
*/
Sub::Sub(void)
: DataFlash(fwver.fw_string, g.log_bitmask),
: DataFlash(g.log_bitmask),
control_mode(MANUAL),
motors(MAIN_LOOP_RATE),
scaleLongDown(1),

View File

@ -24,7 +24,7 @@ void Sub::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());
// load parameters from EEPROM

View File

@ -21,7 +21,7 @@
#include <AP_Common/AP_FWVersion.h>
const AP_FWVersion Sub::fwver{
const AP_FWVersion AP_FWVersion::fwver{
.major = FW_MAJOR,
.minor = FW_MINOR,
.patch = FW_PATCH,
@ -33,9 +33,16 @@ const AP_FWVersion Sub::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
};