mirror of https://github.com/ArduPilot/ardupilot
44 lines
1.3 KiB
C++
44 lines
1.3 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/>.
|
|
*/
|
|
#include "Copter.h"
|
|
|
|
#define FORCE_VERSION_H_INCLUDE
|
|
#include "version.h"
|
|
#undef FORCE_VERSION_H_INCLUDE
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|
|
|
/*
|
|
constructor for main Copter class
|
|
*/
|
|
Copter::Copter(void)
|
|
: logger(g.log_bitmask),
|
|
flight_modes(&g.flight_mode1),
|
|
control_mode(STABILIZE),
|
|
simple_cos_yaw(1.0f),
|
|
super_simple_cos_yaw(1.0),
|
|
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
|
|
rc_throttle_control_in_filter(1.0f),
|
|
inertial_nav(ahrs),
|
|
param_loader(var_info),
|
|
flightmode(&mode_stabilize)
|
|
{
|
|
// init sensor error logging flags
|
|
sensor_health.baro = true;
|
|
sensor_health.compass = true;
|
|
}
|
|
|
|
Copter copter;
|