Browse Source

Copter: use AP_FWVersion singleton

mission-4.1.18
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
485cafb343
  1. 2
      ArduCopter/Copter.cpp
  2. 5
      ArduCopter/GCS_Mavlink.cpp
  3. 1
      ArduCopter/GCS_Mavlink.h
  4. 7
      ArduCopter/system.cpp
  5. 9
      ArduCopter/version.cpp

2
ArduCopter/Copter.cpp

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

5
ArduCopter/GCS_Mavlink.cpp

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

1
ArduCopter/GCS_Mavlink.h

@ -23,7 +23,6 @@ protected:
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override; AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_VisualOdom *get_visual_odom() const override; AP_VisualOdom *get_visual_odom() const override;
const AP_FWVersion &get_fwver() const override;
uint8_t sysid_my_gcs() const override; uint8_t sysid_my_gcs() const override;

7
ArduCopter/system.cpp

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

9
ArduCopter/version.cpp

@ -21,7 +21,7 @@
#include <AP_Common/AP_FWVersion.h> #include <AP_Common/AP_FWVersion.h>
const AP_FWVersion Copter::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 Copter::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
}; };

Loading…
Cancel
Save