mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: use separate header for version macro
Having the version macro in the config.h and consequently in the main vehicle header means that whenever the version changes we need to compiler the whole vehicle again. This would not be so bad if we weren't also appending the git hash in the version. In this case, whenever we commit to the repository we would need to recompile everything. Move to a separate header that is include only by its users. Then instead of compiling everything we will compile just a few files.
This commit is contained in:
parent
352e103f1a
commit
baa287e5e5
|
@ -1,6 +1,7 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Plane.h"
|
||||
#include "version.h"
|
||||
|
||||
// default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
|
||||
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_RC_RECEIVER)
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Plane.h"
|
||||
#include "version.h"
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
|
||||
|
|
|
@ -1,7 +1,4 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Plane.h"
|
||||
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
|
@ -16,13 +13,16 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
constructor for main Plane class
|
||||
*/
|
||||
#include "Plane.h"
|
||||
#include "version.h"
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
/*
|
||||
constructor for main Plane class
|
||||
*/
|
||||
Plane::Plane(void)
|
||||
: DataFlash{FIRMWARE_STRING}
|
||||
{
|
||||
// C++11 doesn't allow in-class initialisation of bitfields
|
||||
auto_state.takeoff_complete = true;
|
||||
|
|
|
@ -1,12 +1,7 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#pragma once
|
||||
|
||||
#define THISFIRMWARE "ArduPlane V3.6.0beta1"
|
||||
#define FIRMWARE_VERSION 3,6,0,FIRMWARE_VERSION_TYPE_BETA
|
||||
|
||||
/*
|
||||
Lead developer: Andrew Tridgell
|
||||
|
||||
|
||||
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Amilcar Lucas, Gregory Fletcher, Paul Riseborough, Brandon Jones, Jon Challinger, Tom Pittenger
|
||||
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier, Yury MonZon
|
||||
|
||||
|
@ -25,6 +20,7 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Header includes
|
||||
|
@ -171,7 +167,7 @@ private:
|
|||
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
||||
AP_Notify notify;
|
||||
|
||||
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
||||
DataFlash_Class DataFlash;
|
||||
|
||||
// has a log download started?
|
||||
bool in_log_download;
|
||||
|
|
|
@ -413,13 +413,3 @@
|
|||
#ifndef PARACHUTE
|
||||
#define PARACHUTE ENABLED
|
||||
#endif
|
||||
|
||||
/*
|
||||
build a firmware version string.
|
||||
GIT_VERSION comes from Makefile builds
|
||||
*/
|
||||
#ifndef GIT_VERSION
|
||||
#define FIRMWARE_STRING THISFIRMWARE
|
||||
#else
|
||||
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
|
||||
#endif
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "Plane.h"
|
||||
#include "version.h"
|
||||
|
||||
/*****************************************************************************
|
||||
* The init_ardupilot function processes everything we need for an in - air restart
|
||||
|
|
|
@ -0,0 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#define THISFIRMWARE "ArduPlane V3.6.0beta1"
|
||||
#define FIRMWARE_VERSION 3,6,0,FIRMWARE_VERSION_TYPE_BETA
|
||||
|
||||
#ifndef GIT_VERSION
|
||||
#define FIRMWARE_STRING THISFIRMWARE
|
||||
#else
|
||||
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
|
||||
#endif
|
Loading…
Reference in New Issue