Sub: add constant structure holding firmware version

This commit is contained in:
Peter Barker 2017-08-19 19:51:55 +10:00 committed by Francisco Ferreira
parent c15c1b84a4
commit ae9891d291
6 changed files with 29 additions and 12 deletions

View File

@ -888,7 +888,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // MAV ID: 21 case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // MAV ID: 21
// 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);
@ -1271,7 +1271,7 @@ void GCS_MAVLINK_Sub::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

@ -20,6 +20,7 @@ protected:
AP_Camera *get_camera() const override; AP_Camera *get_camera() const override;
AP_ServoRelayEvents *get_servorelayevents() const override; AP_ServoRelayEvents *get_servorelayevents() const override;
AP_GPS *get_gps() const override; AP_GPS *get_gps() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
uint8_t sysid_my_gcs() const override; uint8_t sysid_my_gcs() const override;

View File

@ -21,7 +21,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Sub class constructor for main Sub class
*/ */
Sub::Sub(void) : Sub::Sub(void) :
DataFlash {FIRMWARE_STRING, g.log_bitmask}, DataFlash {fwver.fw_string, g.log_bitmask},
mission(ahrs, mission(ahrs,
FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),

View File

@ -82,6 +82,7 @@
#include "Parameters.h" #include "Parameters.h"
#include "AP_Arming_Sub.h" #include "AP_Arming_Sub.h"
#include "GCS_Sub.h" #include "GCS_Sub.h"
#include "version.h"
// libraries which are dependent on #defines in defines.h and/or config.h // libraries which are dependent on #defines in defines.h and/or config.h
#if OPTFLOW == ENABLED #if OPTFLOW == ENABLED
@ -135,6 +136,19 @@ public:
void loop() override; void loop() override;
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

@ -23,9 +23,10 @@ void Sub::init_ardupilot()
// initialise serial port // initialise serial port
serial_manager.init_console(); serial_manager.init_console();
hal.console->printf("\n\nInit " FIRMWARE_STRING hal.console->printf("\n\nInit %s"
"\n\nFree RAM: %u\n", "\n\nFree RAM: %u\n",
(unsigned)hal.util->available_memory()); fwver.fw_string,
(unsigned)hal.util->available_memory());
// load parameters from EEPROM // load parameters from EEPROM
load_parameters(); load_parameters();

View File

@ -1,12 +1,13 @@
#pragma once #pragma once
#include "ap_version.h" #include "AP_Common/AP_FWVersion.h"
#define THISFIRMWARE "ArduSub V3.6-dev" #define THISFIRMWARE "ArduSub 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