diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp
index 8cf95a5628..133c215831 100644
--- a/ArduCopter/Copter.cpp
+++ b/ArduCopter/Copter.cpp
@@ -1,6 +1,5 @@
/// -*- 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
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
along with this program. If not, see .
*/
-/*
- constructor for main Copter class
- */
+#include "Copter.h"
+#include "version.h"
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
+/*
+ constructor for main Copter class
+ */
Copter::Copter(void) :
+ DataFlash{FIRMWARE_STRING},
flight_modes(&g.flight_mode1),
sonar_enabled(true),
mission(ahrs,
diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h
index c7c7ea85a3..dac20a897a 100644
--- a/ArduCopter/Copter.h
+++ b/ArduCopter/Copter.h
@@ -1,9 +1,4 @@
/// -*- 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
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
along with this program. If not, see .
*/
+#pragma once
/*
This is the main Copter class
*/
@@ -162,7 +158,7 @@ private:
RC_Channel *channel_yaw;
// Dataflash
- DataFlash_Class DataFlash{FIRMWARE_STRING};
+ DataFlash_Class DataFlash;
AP_GPS gps;
diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp
index de5bf0bc32..be5e7bd2f9 100644
--- a/ArduCopter/GCS_Mavlink.cpp
+++ b/ArduCopter/GCS_Mavlink.cpp
@@ -1,6 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#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
#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)
diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp
index 9547c2fa63..28ce6078aa 100644
--- a/ArduCopter/Log.cpp
+++ b/ArduCopter/Log.cpp
@@ -1,6 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Copter.h"
+#include "version.h"
#if LOGGING_ENABLED == ENABLED
diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index 4c2753ec2d..5c7c4329ac 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -671,13 +671,3 @@
#ifndef FRSKY_TELEM_ENABLED
# define FRSKY_TELEM_ENABLED 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
diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp
index c181140da2..dca8e6a8f4 100644
--- a/ArduCopter/system.cpp
+++ b/ArduCopter/system.cpp
@@ -1,6 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Copter.h"
+#include "version.h"
/*****************************************************************************
* The init_ardupilot function processes everything we need for an in - air restart
diff --git a/ArduCopter/version.h b/ArduCopter/version.h
new file mode 100644
index 0000000000..d5b95b6c7a
--- /dev/null
+++ b/ArduCopter/version.h
@@ -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