ardupilot/APMrover2/Rover.cpp
Lucas De Marchi 0c49b7a973 APMrover2: move version to a static member
We should never include version.h or ap_version.h headers directly
on a header since this will trigger a complete rebuild of the
codebase when we commit to the repository. The ap_version.h header
is auto-generated containing information from the current commit.

If we include it in a header, every other file that ends up including
that header (directly or indirectly) will need to be rebuilt. No
ccache's cache beats having to do nothing when the header is just
not included.

version.h contains information that is kept on a struct inside
each vehicle. Rather than using the macros from each vehicle,
the getter should be preferred, which returns an AP_FWVersion
referente.
2017-09-23 21:37:45 -07:00

53 lines
1.7 KiB
C++

/*
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
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
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
*/
#include "Rover.h"
#define FORCE_VERSION_H_INCLUDE
#include "version.h"
#undef FORCE_VERSION_H_INCLUDE
Rover::Rover(void) :
param_loader(var_info),
channel_steer(nullptr),
channel_throttle(nullptr),
channel_aux(nullptr),
DataFlash{fwver.fw_string, g.log_bitmask},
modes(&g.mode1),
L1_controller(ahrs, nullptr),
nav_controller(&L1_controller),
mission(ahrs,
FUNCTOR_BIND_MEMBER(&Rover::start_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::verify_command_callback, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&Rover::exit_mission, void)),
ServoRelayEvents(relay),
#if CAMERA == ENABLED
camera(&relay, MASK_LOG_CAMERA, current_loc, gps, ahrs),
#endif
#if MOUNT == ENABLED
camera_mount(ahrs, current_loc),
#endif
control_mode(&mode_initializing),
#if FRSKY_TELEM_ENABLED == ENABLED
frsky_telemetry(ahrs, battery, rangefinder),
#endif
home(ahrs.get_home()),
G_Dt(0.02f)
{
}