ardupilot/ArduSub/Sub.cpp

54 lines
1.8 KiB
C++
Raw Normal View History

/*
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 "Sub.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 Sub class
*/
Sub::Sub()
: logger(g.log_bitmask),
control_mode(MANUAL),
motors(MAIN_LOOP_RATE),
scaleLongDown(1),
auto_mode(Auto_WP),
guided_mode(Guided_WP),
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
inertial_nav(ahrs),
2017-02-20 14:30:35 -04:00
ahrs_view(ahrs, ROTATION_NONE),
attitude_control(ahrs_view, aparm, motors, MAIN_LOOP_SECONDS),
2021-04-27 03:50:06 -03:00
pos_control(ahrs_view, inertial_nav, motors, attitude_control, MAIN_LOOP_SECONDS),
2017-02-20 14:30:35 -04:00
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
2018-03-28 01:54:24 -03:00
loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
2017-02-20 14:30:35 -04:00
circle_nav(inertial_nav, ahrs_view, pos_control),
param_loader(var_info)
{
// init sensor error logging flags
sensor_health.baro = true;
sensor_health.compass = true;
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
failsafe.pilot_input = true;
#endif
}
2016-01-14 15:30:56 -04:00
Sub sub;
AP_Vehicle& vehicle = sub;