Browse Source

APMrover2: 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.
mission-4.1.18
Lucas De Marchi 9 years ago
parent
commit
d3ee998fa6
  1. 1
      APMrover2/GCS_Mavlink.cpp
  2. 1
      APMrover2/Log.cpp
  3. 2
      APMrover2/Rover.cpp
  4. 7
      APMrover2/Rover.h
  5. 10
      APMrover2/config.h
  6. 1
      APMrover2/system.cpp
  7. 10
      APMrover2/version.h

1
APMrover2/GCS_Mavlink.cpp

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
#include "version.h"
// default sensors are present and healthy: gyro, accelerometer, 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_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS)

1
APMrover2/Log.cpp

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
#include "version.h"
#if LOGGING_ENABLED == ENABLED

2
APMrover2/Rover.cpp

@ -18,12 +18,14 @@ @@ -18,12 +18,14 @@
*/
#include "Rover.h"
#include "version.h"
Rover::Rover(void) :
param_loader(var_info),
channel_steer(NULL),
channel_throttle(NULL),
channel_learn(NULL),
DataFlash{FIRMWARE_STRING},
in_log_download(false),
modes(&g.mode1),
L1_controller(ahrs),

7
APMrover2/Rover.h

@ -13,14 +13,11 @@ @@ -13,14 +13,11 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
/*
main Rover class, containing all vehicle specific state
*/
#pragma once
#define THISFIRMWARE "ArduRover v3.0.0"
#define FIRMWARE_VERSION 3,0,0,FIRMWARE_VERSION_TYPE_OFFICIAL
#include <cmath>
#include <stdarg.h>
@ -128,7 +125,7 @@ private: @@ -128,7 +125,7 @@ private:
RC_Channel *channel_throttle;
RC_Channel *channel_learn;
DataFlash_Class DataFlash{FIRMWARE_STRING};
DataFlash_Class DataFlash;
bool in_log_download;

10
APMrover2/config.h

@ -303,13 +303,3 @@ @@ -303,13 +303,3 @@
#ifndef SONAR_ENABLED
# define SONAR_ENABLED DISABLED
#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
APMrover2/system.cpp

@ -7,6 +7,7 @@ The init_ardupilot function processes everything we need for an in - air restart @@ -7,6 +7,7 @@ The init_ardupilot function processes everything we need for an in - air restart
*****************************************************************************/
#include "Rover.h"
#include "version.h"
#if CLI_ENABLED == ENABLED

10
APMrover2/version.h

@ -0,0 +1,10 @@ @@ -0,0 +1,10 @@
#pragma once
#define THISFIRMWARE "ArduRover v3.0.0"
#define FIRMWARE_VERSION 3,0,0,FIRMWARE_VERSION_TYPE_OFFICIAL
#ifndef GIT_VERSION
#define FIRMWARE_STRING THISFIRMWARE
#else
#define FIRMWARE_STRING THISFIRMWARE " (" GIT_VERSION ")"
#endif
Loading…
Cancel
Save