Rover: add constant structure holding firmware version

This commit is contained in:
Peter Barker 2017-08-19 20:04:56 +10:00 committed by Francisco Ferreira
parent 0177e959c9
commit d98c427514
5 changed files with 25 additions and 10 deletions

View File

@ -944,7 +944,7 @@ void GCS_MAVLINK_Rover::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);

View File

@ -24,7 +24,7 @@ Rover::Rover(void) :
channel_steer(nullptr),
channel_throttle(nullptr),
channel_aux(nullptr),
DataFlash{FIRMWARE_STRING, g.log_bitmask},
DataFlash{fwver.fw_string, g.log_bitmask},
modes(&g.mode1),
L1_controller(ahrs, nullptr),
nav_controller(&L1_controller),

View File

@ -92,6 +92,7 @@
#include "Parameters.h"
#include "GCS_Mavlink.h"
#include "GCS_Rover.h"
#include "version.h"
class Rover : public AP_HAL::HAL::Callbacks {
public:
@ -119,6 +120,18 @@ public:
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
};
// must be the first AP_Param variable declared to ensure its
// constructor runs before the constructors of the other AP_Param
// variables

View File

@ -23,8 +23,9 @@ void Rover::init_ardupilot()
// initialise console 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,
hal.util->available_memory());
//
@ -79,7 +80,7 @@ void Rover::init_ardupilot()
// setup frsky telemetry
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry.init(serial_manager, FIRMWARE_STRING, MAV_TYPE_GROUND_ROVER);
frsky_telemetry.init(serial_manager, fwver.fw_string, MAV_TYPE_GROUND_ROVER);
#endif
#if LOGGING_ENABLED == ENABLED

View File

@ -1,12 +1,13 @@
#pragma once
#include "ap_version.h"
#include "AP_Common/AP_FWVersion.h"
#define THISFIRMWARE "APM:Rover V3.2.0-dev"
// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 3,2,0,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 2
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV