Copter: add constant structure holding firmware version

This commit is contained in:
Peter Barker 2017-08-19 08:45:02 +10:00 committed by Francisco Ferreira
parent e9204a66ee
commit 470e790117
5 changed files with 27 additions and 11 deletions

View File

@ -21,7 +21,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{FIRMWARE_STRING, g.log_bitmask}, DataFlash{fwver.fw_string, g.log_bitmask},
flight_modes(&g.flight_mode1), flight_modes(&g.flight_mode1),
mission(ahrs, mission(ahrs,
FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &),

View File

@ -127,6 +127,7 @@
// Local modules // Local modules
#include "Parameters.h" #include "Parameters.h"
#include "avoidance_adsb.h" #include "avoidance_adsb.h"
#include "version.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h> #include <SITL/SITL.h>
@ -163,6 +164,19 @@ public:
}; };
private: private:
const AP_FWVersion fwver {
major: FW_MAJOR,
minor: FW_MINOR,
patch: FW_PATCH,
fw_type: FW_TYPE,
#ifndef GIT_VERSION
fw_string: THISFIRMWARE
#else
fw_string: THISFIRMWARE " (" GIT_VERSION ")"
#endif
};
// key aircraft parameters passed to multiple libraries // key aircraft parameters passed to multiple libraries
AP_Vehicle::MultiCopter aparm; AP_Vehicle::MultiCopter aparm;

View File

@ -724,7 +724,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
} }
// mark the firmware version in the tlog // mark the firmware version in the tlog
send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING); send_text(MAV_SEVERITY_INFO, fwver.fw_string);
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION) #if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION); send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
@ -1160,7 +1160,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
case MAV_CMD_DO_SEND_BANNER: { case MAV_CMD_DO_SEND_BANNER: {
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
send_text(MAV_SEVERITY_INFO, FIRMWARE_STRING); send_text(MAV_SEVERITY_INFO, fwver.fw_string);
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION) #if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION); send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);

View File

@ -36,8 +36,9 @@ void Copter::init_ardupilot()
// init vehicle capabilties // init vehicle capabilties
init_capabilities(); init_capabilities();
hal.console->printf("\n\nInit " FIRMWARE_STRING hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n", "\n\nFree RAM: %u\n",
fwver.fw_string,
(unsigned)hal.util->available_memory()); (unsigned)hal.util->available_memory());
// //
@ -100,7 +101,7 @@ 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]; char firmware_buf[50];
snprintf(firmware_buf, sizeof(firmware_buf), FIRMWARE_STRING " %s", get_frame_string()); 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, firmware_buf,
get_frame_mav_type(), get_frame_mav_type(),
&g.fs_batt_voltage, &g.fs_batt_mah, &ap.value); &g.fs_batt_voltage, &g.fs_batt_mah, &ap.value);

View File

@ -1,12 +1,13 @@
#pragma once #pragma once
#include "ap_version.h" #include "AP_Common/AP_FWVersion.h"
#define THISFIRMWARE "APM:Copter V3.6-dev" #define THISFIRMWARE "APM:Copter V3.6-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 3,6,0,FIRMWARE_VERSION_TYPE_DEV #define FIRMWARE_VERSION 3,6,0,FIRMWARE_VERSION_TYPE_DEV
#ifndef GIT_VERSION #define FW_MAJOR 3
#define FIRMWARE_STRING THISFIRMWARE #define FW_MINOR 6
#else #define FW_PATCH 0
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")" #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV
#endif