mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduCopter: 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
d3ee998fa6
commit
352e103f1a
@ -1,6 +1,5 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#include "Copter.h"
|
|
||||||
/*
|
/*
|
||||||
This program is free software: you can redistribute it and/or modify
|
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
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -15,13 +14,16 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
/*
|
#include "Copter.h"
|
||||||
constructor for main Copter class
|
#include "version.h"
|
||||||
*/
|
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
|
/*
|
||||||
|
constructor for main Copter class
|
||||||
|
*/
|
||||||
Copter::Copter(void) :
|
Copter::Copter(void) :
|
||||||
|
DataFlash{FIRMWARE_STRING},
|
||||||
flight_modes(&g.flight_mode1),
|
flight_modes(&g.flight_mode1),
|
||||||
sonar_enabled(true),
|
sonar_enabled(true),
|
||||||
mission(ahrs,
|
mission(ahrs,
|
||||||
|
@ -1,9 +1,4 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#define THISFIRMWARE "APM:Copter V3.4-dev"
|
|
||||||
#define FIRMWARE_VERSION 3,4,0,FIRMWARE_VERSION_TYPE_DEV
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
This program is free software: you can redistribute it and/or modify
|
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
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -18,6 +13,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
/*
|
/*
|
||||||
This is the main Copter class
|
This is the main Copter class
|
||||||
*/
|
*/
|
||||||
@ -162,7 +158,7 @@ private:
|
|||||||
RC_Channel *channel_yaw;
|
RC_Channel *channel_yaw;
|
||||||
|
|
||||||
// Dataflash
|
// Dataflash
|
||||||
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
DataFlash_Class DataFlash;
|
||||||
|
|
||||||
AP_GPS gps;
|
AP_GPS gps;
|
||||||
|
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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
|
// 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)
|
#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)
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
#include "version.h"
|
||||||
|
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
|
||||||
|
@ -671,13 +671,3 @@
|
|||||||
#ifndef FRSKY_TELEM_ENABLED
|
#ifndef FRSKY_TELEM_ENABLED
|
||||||
# define FRSKY_TELEM_ENABLED ENABLED
|
# define FRSKY_TELEM_ENABLED ENABLED
|
||||||
#endif
|
#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 -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
#include "version.h"
|
||||||
|
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
* The init_ardupilot function processes everything we need for an in - air restart
|
* The init_ardupilot function processes everything we need for an in - air restart
|
||||||
|
10
ArduCopter/version.h
Normal file
10
ArduCopter/version.h
Normal file
@ -0,0 +1,10 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define THISFIRMWARE "APM:Copter V3.4-dev"
|
||||||
|
#define FIRMWARE_VERSION 3,4,0,FIRMWARE_VERSION_TYPE_DEV
|
||||||
|
|
||||||
|
#ifndef GIT_VERSION
|
||||||
|
#define FIRMWARE_STRING THISFIRMWARE
|
||||||
|
#else
|
||||||
|
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
|
||||||
|
#endif
|
Loading…
Reference in New Issue
Block a user