mirror of https://github.com/ArduPilot/ardupilot
Plane: add constant structure holding firmware version
This commit is contained in:
parent
470e790117
commit
c15c1b84a4
|
@ -1400,7 +1400,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
|
||||
{
|
||||
// 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)
|
||||
send_text(MAV_SEVERITY_INFO, "PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION);
|
||||
|
@ -1920,4 +1920,3 @@ bool GCS_MAVLINK_Plane::set_mode(const uint8_t mode)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
constructor for main Plane class
|
||||
*/
|
||||
Plane::Plane(void)
|
||||
: DataFlash{FIRMWARE_STRING, g.log_bitmask}
|
||||
: DataFlash{fwver.fw_string, g.log_bitmask}
|
||||
{
|
||||
// C++11 doesn't allow in-class initialisation of bitfields
|
||||
auto_state.takeoff_complete = true;
|
||||
|
|
|
@ -110,6 +110,7 @@
|
|||
#include "Parameters.h"
|
||||
#include "avoidance_adsb.h"
|
||||
#include "AP_Arming.h"
|
||||
#include "version.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
|
@ -156,6 +157,19 @@ public:
|
|||
void loop() override;
|
||||
|
||||
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
|
||||
AP_Vehicle::FixedWing aparm;
|
||||
|
||||
|
|
|
@ -23,8 +23,9 @@ void Plane::init_ardupilot()
|
|||
// initialise serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
hal.console->printf("\n\nInit " FIRMWARE_STRING
|
||||
hal.console->printf("\n\nInit %s"
|
||||
"\n\nFree RAM: %u\n",
|
||||
fwver.fw_string,
|
||||
(unsigned)hal.util->available_memory());
|
||||
|
||||
|
||||
|
@ -114,7 +115,7 @@ void Plane::init_ardupilot()
|
|||
// setup frsky
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// setup frsky, and pass a number of parameters to the library
|
||||
frsky_telemetry.init(serial_manager, FIRMWARE_STRING,
|
||||
frsky_telemetry.init(serial_manager, fwver.fw_string,
|
||||
MAV_TYPE_FIXED_WING,
|
||||
&g.fs_batt_voltage, &g.fs_batt_mah);
|
||||
#endif
|
||||
|
|
|
@ -1,12 +1,13 @@
|
|||
#pragma once
|
||||
|
||||
#include "ap_version.h"
|
||||
#include "AP_Common/AP_FWVersion.h"
|
||||
|
||||
#define THISFIRMWARE "ArduPlane V3.8.1-dev"
|
||||
|
||||
// the following line is parsed by the autotest scripts
|
||||
#define FIRMWARE_VERSION 3,8,1,FIRMWARE_VERSION_TYPE_DEV
|
||||
|
||||
#ifndef GIT_VERSION
|
||||
#define FIRMWARE_STRING THISFIRMWARE
|
||||
#else
|
||||
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
|
||||
#endif
|
||||
#define FW_MAJOR 3
|
||||
#define FW_MINOR 8
|
||||
#define FW_PATCH 1
|
||||
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV
|
||||
|
|
Loading…
Reference in New Issue