2015-05-29 23:12:49 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
2016-05-05 19:10:08 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
#include "version.h"
|
2015-05-29 23:12:49 -03:00
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2015-05-29 23:12:49 -03:00
|
|
|
|
2016-05-05 19:10:08 -03:00
|
|
|
/*
|
|
|
|
constructor for main Copter class
|
|
|
|
*/
|
2015-05-29 23:12:49 -03:00
|
|
|
Copter::Copter(void) :
|
2016-05-05 19:10:08 -03:00
|
|
|
DataFlash{FIRMWARE_STRING},
|
2015-05-29 23:12:49 -03:00
|
|
|
flight_modes(&g.flight_mode1),
|
|
|
|
mission(ahrs,
|
|
|
|
FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &),
|
2015-07-20 04:08:00 -03:00
|
|
|
FUNCTOR_BIND_MEMBER(&Copter::verify_command_callback, bool, const AP_Mission::Mission_Command &),
|
2015-05-29 23:12:49 -03:00
|
|
|
FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void)),
|
|
|
|
control_mode(STABILIZE),
|
|
|
|
scaleLongDown(1),
|
2015-06-08 01:02:20 -03:00
|
|
|
wp_bearing(0),
|
|
|
|
home_bearing(0),
|
|
|
|
home_distance(0),
|
|
|
|
wp_distance(0),
|
|
|
|
auto_mode(Auto_TakeOff),
|
|
|
|
guided_mode(Guided_TakeOff),
|
|
|
|
rtl_state(RTL_InitialClimb),
|
|
|
|
rtl_state_complete(false),
|
|
|
|
circle_pilot_yaw_override(false),
|
2015-05-29 23:12:49 -03:00
|
|
|
simple_cos_yaw(1.0f),
|
2015-06-08 01:02:20 -03:00
|
|
|
simple_sin_yaw(0.0f),
|
|
|
|
super_simple_last_bearing(0),
|
2015-05-29 23:12:49 -03:00
|
|
|
super_simple_cos_yaw(1.0),
|
2015-06-08 01:02:20 -03:00
|
|
|
super_simple_sin_yaw(0.0f),
|
|
|
|
initial_armed_bearing(0),
|
|
|
|
desired_climb_rate(0),
|
|
|
|
loiter_time_max(0),
|
|
|
|
loiter_time(0),
|
2015-05-29 23:12:49 -03:00
|
|
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
2016-08-09 19:17:13 -03:00
|
|
|
frsky_telemetry(ahrs, battery, rangefinder),
|
2015-05-29 23:12:49 -03:00
|
|
|
#endif
|
2015-06-08 01:02:20 -03:00
|
|
|
climb_rate(0),
|
2016-04-27 08:37:04 -03:00
|
|
|
target_rangefinder_alt(0.0f),
|
2015-06-08 01:02:20 -03:00
|
|
|
baro_alt(0),
|
|
|
|
baro_climbrate(0.0f),
|
2015-05-29 23:12:49 -03:00
|
|
|
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
|
2016-01-06 17:39:36 -04:00
|
|
|
rc_throttle_control_in_filter(1.0f),
|
2015-05-29 23:12:49 -03:00
|
|
|
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
|
2015-06-08 01:02:20 -03:00
|
|
|
yaw_look_at_WP_bearing(0.0f),
|
|
|
|
yaw_look_at_heading(0),
|
|
|
|
yaw_look_at_heading_slew(0),
|
|
|
|
yaw_look_ahead_bearing(0.0f),
|
|
|
|
condition_value(0),
|
|
|
|
condition_start(0),
|
2016-02-17 06:59:31 -04:00
|
|
|
G_Dt(MAIN_LOOP_SECONDS),
|
2015-05-29 23:12:49 -03:00
|
|
|
inertial_nav(ahrs),
|
2015-06-08 01:02:20 -03:00
|
|
|
pmTest1(0),
|
|
|
|
fast_loopTimer(0),
|
|
|
|
mainLoop_count(0),
|
|
|
|
rtl_loiter_start_time(0),
|
|
|
|
auto_trim_counter(0),
|
2015-05-29 23:12:49 -03:00
|
|
|
ServoRelayEvents(relay),
|
|
|
|
#if CAMERA == ENABLED
|
|
|
|
camera(&relay),
|
|
|
|
#endif
|
|
|
|
#if MOUNT == ENABLED
|
|
|
|
camera_mount(ahrs, current_loc),
|
|
|
|
#endif
|
|
|
|
#if AC_FENCE == ENABLED
|
2016-07-02 05:15:05 -03:00
|
|
|
fence(ahrs, inertial_nav),
|
2015-05-29 23:12:49 -03:00
|
|
|
#endif
|
2017-01-02 20:36:26 -04:00
|
|
|
#if AC_AVOID_ENABLED == ENABLED
|
2016-12-01 11:34:14 -04:00
|
|
|
avoid(ahrs, inertial_nav, fence, g2.proximity),
|
2017-01-02 20:36:26 -04:00
|
|
|
#endif
|
2015-05-29 23:12:49 -03:00
|
|
|
#if AC_RALLY == ENABLED
|
|
|
|
rally(ahrs),
|
|
|
|
#endif
|
|
|
|
#if SPRAYER == ENABLED
|
|
|
|
sprayer(&inertial_nav),
|
|
|
|
#endif
|
|
|
|
#if PARACHUTE == ENABLED
|
|
|
|
parachute(relay),
|
|
|
|
#endif
|
2015-11-13 23:38:47 -04:00
|
|
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
2015-05-29 23:12:49 -03:00
|
|
|
terrain(ahrs, mission, rally),
|
2015-02-16 00:39:18 -04:00
|
|
|
#endif
|
|
|
|
#if PRECISION_LANDING == ENABLED
|
2016-05-05 23:04:42 -03:00
|
|
|
precland(ahrs, inertial_nav),
|
2015-11-27 02:18:17 -04:00
|
|
|
#endif
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
|
|
|
|
input_manager(MAIN_LOOP_RATE),
|
2015-05-29 23:12:49 -03:00
|
|
|
#endif
|
2015-06-08 01:02:20 -03:00
|
|
|
in_mavlink_delay(false),
|
|
|
|
gcs_out_of_time(false),
|
2015-09-24 03:57:22 -03:00
|
|
|
param_loader(var_info)
|
2015-05-29 23:12:49 -03:00
|
|
|
{
|
2015-06-08 01:02:20 -03:00
|
|
|
memset(¤t_loc, 0, sizeof(current_loc));
|
2015-07-12 10:06:21 -03:00
|
|
|
|
|
|
|
// init sensor error logging flags
|
|
|
|
sensor_health.baro = true;
|
|
|
|
sensor_health.compass = true;
|
2015-05-29 23:12:49 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
Copter copter;
|