Copter: use AP_FWVersion singleton

This commit is contained in:
Peter Barker 2018-06-13 21:28:01 +10:00 committed by Francisco Ferreira
parent ab6cf171da
commit 485cafb343
5 changed files with 12 additions and 12 deletions

View File

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

View File

@ -1700,8 +1700,3 @@ bool GCS_MAVLINK_Copter::set_mode(const uint8_t mode)
#endif
return copter.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
const AP_FWVersion &GCS_MAVLINK_Copter::get_fwver() const
{
return copter.fwver;
}

View File

@ -23,7 +23,6 @@ protected:
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) 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;

View File

@ -28,7 +28,7 @@ void Copter::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());
//
@ -99,11 +99,10 @@ void Copter::init_ardupilot()
#if FRSKY_TELEM_ENABLED == ENABLED
// setup frsky, and pass a number of parameters to the library
char firmware_buf[50];
snprintf(firmware_buf, sizeof(firmware_buf), "%s %s", fwver.fw_string, get_frame_string());
frsky_telemetry.init(serial_manager, firmware_buf,
frsky_telemetry.init(serial_manager,
get_frame_mav_type(),
&ap.value);
frsky_telemetry.set_frame_string(get_frame_string());
#endif
#if DEVO_TELEM_ENABLED == ENABLED

View File

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