2015-12-30 18:57:56 -04: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/>.
|
|
|
|
*/
|
2017-02-03 00:18:27 -04:00
|
|
|
#pragma once
|
2015-12-30 18:57:56 -04:00
|
|
|
/*
|
2016-01-14 15:30:56 -04:00
|
|
|
This is the main Sub class
|
2015-12-30 18:57:56 -04:00
|
|
|
*/
|
|
|
|
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Header includes
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
|
2016-04-10 17:32:50 -03:00
|
|
|
#include <cmath>
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <stdio.h>
|
|
|
|
#include <stdarg.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
// Common dependencies
|
|
|
|
#include <AP_Common/AP_Common.h>
|
2016-05-03 01:45:37 -03:00
|
|
|
#include <AP_Common/Location.h>
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <StorageManager/StorageManager.h>
|
2017-04-13 15:58:43 -03:00
|
|
|
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
|
|
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
|
|
|
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Application dependencies
|
|
|
|
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h> // Mission command library
|
2017-02-02 23:17:44 -04:00
|
|
|
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library
|
2022-07-03 15:57:24 -03:00
|
|
|
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <AP_Motors/AP_Motors.h> // AP Motors library
|
|
|
|
#include <Filter/Filter.h> // Filter library
|
|
|
|
#include <AP_Relay/AP_Relay.h> // APM relay
|
|
|
|
#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
|
2021-10-18 23:15:01 -03:00
|
|
|
#include <AP_InertialNav/AP_InertialNav.h> // inertial navigation library
|
2017-02-10 13:46:54 -04:00
|
|
|
#include <AC_WPNav/AC_WPNav.h> // Waypoint navigation library
|
2018-03-28 01:54:24 -03:00
|
|
|
#include <AC_WPNav/AC_Loiter.h>
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <AC_WPNav/AC_Circle.h> // circle navigation library
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
2017-11-12 22:08:00 -04:00
|
|
|
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
|
2015-12-30 18:57:56 -04:00
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
2016-02-20 15:32:42 -04:00
|
|
|
#include <AP_Terrain/AP_Terrain.h>
|
2016-03-12 11:15:18 -04:00
|
|
|
#include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
|
2017-02-28 17:55:00 -04:00
|
|
|
#include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
|
2021-03-25 05:09:38 -03:00
|
|
|
#include <AP_Proximity/AP_Proximity.h>
|
2017-04-13 15:58:43 -03:00
|
|
|
|
|
|
|
// Local modules
|
2016-02-20 15:32:42 -04:00
|
|
|
#include "defines.h"
|
|
|
|
#include "config.h"
|
2016-06-08 01:49:10 -03:00
|
|
|
#include "GCS_Mavlink.h"
|
2018-04-26 23:26:38 -03:00
|
|
|
#include "RC_Channel.h" // RC Channel Library
|
2017-04-13 15:58:43 -03:00
|
|
|
#include "Parameters.h"
|
|
|
|
#include "AP_Arming_Sub.h"
|
2017-02-21 20:54:56 -04:00
|
|
|
#include "GCS_Sub.h"
|
2016-06-08 01:49:10 -03:00
|
|
|
|
2017-04-11 16:32:03 -03:00
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
|
|
|
|
|
2021-12-24 18:05:23 -04:00
|
|
|
// libraries which are dependent on #defines in defines.h and/or config.h
|
2016-11-25 20:06:07 -04:00
|
|
|
#if RCMAP_ENABLED == ENABLED
|
|
|
|
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
|
|
|
#endif
|
|
|
|
|
2022-07-15 20:59:13 -03:00
|
|
|
#include <AP_RPM/AP_RPM_config.h>
|
|
|
|
|
|
|
|
#if AP_RPM_ENABLED
|
2016-11-25 20:06:07 -04:00
|
|
|
#include <AP_RPM/AP_RPM.h>
|
|
|
|
#endif
|
|
|
|
|
2022-09-20 04:37:48 -03:00
|
|
|
#include <AP_Gripper/AP_Gripper_config.h>
|
|
|
|
#if AP_GRIPPER_ENABLED
|
2016-11-17 01:12:06 -04:00
|
|
|
#include <AP_Gripper/AP_Gripper.h> // gripper stuff
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2016-12-04 12:49:46 -04:00
|
|
|
#if AVOIDANCE_ENABLED == ENABLED
|
2017-02-10 13:46:54 -04:00
|
|
|
#include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
|
2016-12-04 12:49:46 -04:00
|
|
|
#endif
|
|
|
|
|
2017-04-13 00:15:51 -03:00
|
|
|
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
|
|
|
|
2021-11-15 01:08:34 -04:00
|
|
|
#if AP_SCRIPTING_ENABLED
|
2019-03-01 02:41:05 -04:00
|
|
|
#include <AP_Scripting/AP_Scripting.h>
|
|
|
|
#endif
|
|
|
|
|
2018-12-27 02:34:29 -04:00
|
|
|
class Sub : public AP_Vehicle {
|
2015-12-30 18:57:56 -04:00
|
|
|
public:
|
2016-06-08 01:49:10 -03:00
|
|
|
friend class GCS_MAVLINK_Sub;
|
2017-02-21 20:54:56 -04:00
|
|
|
friend class GCS_Sub;
|
2015-12-30 18:57:56 -04:00
|
|
|
friend class Parameters;
|
2016-11-17 01:12:06 -04:00
|
|
|
friend class ParametersG2;
|
2017-02-27 17:12:56 -04:00
|
|
|
friend class AP_Arming_Sub;
|
2018-04-26 23:26:38 -03:00
|
|
|
friend class RC_Channels_Sub;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
Sub(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2020-09-27 22:21:53 -03:00
|
|
|
protected:
|
|
|
|
|
|
|
|
bool should_zero_rc_outputs_on_reboot() const override { return true; }
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
private:
|
2017-08-19 06:51:55 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// key aircraft parameters passed to multiple libraries
|
2022-09-29 20:10:41 -03:00
|
|
|
AP_MultiCopter aparm;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Global parameters are all contained within the 'g' class.
|
|
|
|
Parameters g;
|
2016-07-23 02:50:24 -03:00
|
|
|
ParametersG2 g2;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// primary input control channels
|
|
|
|
RC_Channel *channel_roll;
|
|
|
|
RC_Channel *channel_pitch;
|
|
|
|
RC_Channel *channel_throttle;
|
|
|
|
RC_Channel *channel_yaw;
|
2017-02-07 23:51:37 -04:00
|
|
|
RC_Channel *channel_forward;
|
2016-04-10 18:43:35 -03:00
|
|
|
RC_Channel *channel_lateral;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
AP_Logger logger;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-12-12 21:06:15 -04:00
|
|
|
AP_LeakDetector leak_detector;
|
2017-02-07 19:47:30 -04:00
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
struct {
|
|
|
|
bool enabled:1;
|
|
|
|
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
|
|
|
|
int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder
|
|
|
|
uint32_t last_healthy_ms;
|
|
|
|
LowPassFilterFloat alt_cm_filt; // altitude filter
|
|
|
|
} rangefinder_state = { false, false, 0, 0 };
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2022-07-15 20:59:13 -03:00
|
|
|
#if AP_RPM_ENABLED
|
2017-12-12 21:06:15 -04:00
|
|
|
AP_RPM rpm_sensor;
|
2016-11-25 18:58:31 -04:00
|
|
|
#endif
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Mission library
|
2018-04-24 20:09:49 -03:00
|
|
|
AP_Mission mission{
|
2017-08-28 18:31:45 -03:00
|
|
|
FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
|
|
|
|
FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),
|
2017-12-12 21:06:15 -04:00
|
|
|
FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Optical flow sensor
|
2021-12-24 18:05:23 -04:00
|
|
|
#if AP_OPTICALFLOW_ENABLED
|
2022-08-14 22:31:15 -03:00
|
|
|
AP_OpticalFlow optflow;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// system time in milliseconds of last recorded yaw reset from ekf
|
|
|
|
uint32_t ekfYawReset_ms = 0;
|
|
|
|
|
2017-08-28 19:03:27 -03:00
|
|
|
// GCS selection
|
2017-02-21 20:54:56 -04:00
|
|
|
GCS_Sub _gcs; // avoid using this; use gcs()
|
|
|
|
GCS_Sub &gcs() { return _gcs; }
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// User variables
|
|
|
|
#ifdef USERHOOK_VARIABLES
|
|
|
|
# include USERHOOK_VARIABLES
|
|
|
|
#endif
|
|
|
|
|
2017-03-01 00:05:51 -04:00
|
|
|
// Documentation of Globals:
|
2015-12-30 18:57:56 -04:00
|
|
|
union {
|
|
|
|
struct {
|
2017-03-01 00:05:51 -04:00
|
|
|
uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
|
2019-02-11 04:11:57 -04:00
|
|
|
uint8_t logging_started : 1; // true if logging has started
|
2017-03-01 00:05:51 -04:00
|
|
|
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
|
|
|
|
uint8_t motor_test : 1; // true if we are currently performing the motors test
|
|
|
|
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
|
|
|
uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
|
|
|
|
uint8_t at_bottom : 1; // true if we are at the bottom
|
|
|
|
uint8_t at_surface : 1; // true if we are at the surface
|
2017-05-03 19:13:06 -03:00
|
|
|
uint8_t depth_sensor_present: 1; // true if there is a depth sensor detected at boot
|
2020-02-18 12:04:44 -04:00
|
|
|
uint8_t unused1 : 1; // was compass_init_location; true when the compass's initial location has been set
|
2015-12-30 18:57:56 -04:00
|
|
|
};
|
|
|
|
uint32_t value;
|
|
|
|
} ap;
|
|
|
|
|
|
|
|
// This is the state of the flight control system
|
|
|
|
// There are multiple states defined such as STABILIZE, ACRO,
|
2016-04-18 01:38:21 -03:00
|
|
|
control_mode_t control_mode;
|
|
|
|
|
|
|
|
control_mode_t prev_control_mode;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-11-25 19:26:28 -04:00
|
|
|
#if RCMAP_ENABLED == ENABLED
|
2017-12-12 21:06:15 -04:00
|
|
|
RCMapper rcmap;
|
2016-11-25 19:26:28 -04:00
|
|
|
#endif
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Failsafe
|
|
|
|
struct {
|
2016-08-19 14:54:22 -03:00
|
|
|
uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
|
2016-08-26 16:27:28 -03:00
|
|
|
uint32_t last_gcs_warn_ms;
|
2017-04-14 16:58:54 -03:00
|
|
|
uint32_t last_pilot_input_ms; // last time we received pilot input in the form of MANUAL_CONTROL or RC_CHANNELS_OVERRIDE messages
|
2016-05-03 01:45:37 -03:00
|
|
|
uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
|
|
|
|
uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
|
2017-03-24 17:30:28 -03:00
|
|
|
uint32_t last_crash_warn_ms; // last time a crash warning was sent to gcs
|
2017-04-08 11:36:16 -03:00
|
|
|
uint32_t last_ekf_warn_ms; // last time an ekf warning was sent to gcs
|
2018-03-01 14:44:02 -04:00
|
|
|
|
|
|
|
uint8_t pilot_input : 1; // true if pilot input failsafe is active, handles things like joystick being disconnected during operation
|
|
|
|
uint8_t gcs : 1; // A status flag for the ground station failsafe
|
|
|
|
uint8_t ekf : 1; // true if ekf failsafe has occurred
|
|
|
|
uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred
|
|
|
|
uint8_t leak : 1; // true if leak recently detected
|
|
|
|
uint8_t internal_pressure : 1; // true if internal pressure is over threshold
|
|
|
|
uint8_t internal_temperature : 1; // true if temperature is over threshold
|
|
|
|
uint8_t crash : 1; // true if we are crashed
|
|
|
|
uint8_t sensor_health : 1; // true if at least one sensor has triggered a failsafe (currently only used for depth in depth enabled modes)
|
2015-12-30 18:57:56 -04:00
|
|
|
} failsafe;
|
|
|
|
|
2018-03-22 06:38:37 -03:00
|
|
|
bool any_failsafe_triggered() const {
|
|
|
|
return (failsafe.pilot_input || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain);
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// sensor health for logging
|
|
|
|
struct {
|
2017-04-15 02:03:56 -03:00
|
|
|
uint8_t depth : 1; // true if depth sensor is healthy
|
2015-12-30 18:57:56 -04:00
|
|
|
uint8_t compass : 1; // true if compass is healthy
|
|
|
|
} sensor_health;
|
|
|
|
|
2017-04-15 02:03:56 -03:00
|
|
|
// Baro sensor instance index of the external water pressure sensor
|
|
|
|
uint8_t depth_sensor_idx;
|
|
|
|
|
2016-12-13 21:15:37 -04:00
|
|
|
AP_Motors6DOF motors;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Auto
|
|
|
|
AutoMode auto_mode; // controls which auto controller is run
|
|
|
|
|
|
|
|
// Guided
|
|
|
|
GuidedMode guided_mode; // controls which controller is run (pos or vel)
|
|
|
|
|
|
|
|
// Circle
|
|
|
|
bool circle_pilot_yaw_override; // true if pilot is overriding yaw
|
|
|
|
|
2017-04-06 18:31:40 -03:00
|
|
|
// Stores initial bearing when armed
|
2015-12-30 18:57:56 -04:00
|
|
|
int32_t initial_armed_bearing;
|
|
|
|
|
|
|
|
// Throttle variables
|
|
|
|
int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
|
|
|
|
|
|
|
|
// Loiter control
|
|
|
|
uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
|
|
|
|
uint32_t loiter_time; // How long have we been loitering - The start time in millis
|
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
// Delay the next navigation command
|
2019-08-09 15:42:00 -03:00
|
|
|
uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands
|
|
|
|
uint32_t nav_delay_time_start_ms;
|
2016-05-22 21:50:44 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Battery Sensors
|
2018-03-01 14:44:02 -04:00
|
|
|
AP_BattMonitor battery{MASK_LOG_CURRENT,
|
|
|
|
FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),
|
|
|
|
_failsafe_priorities};
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-06-25 02:26:41 -03:00
|
|
|
AP_Arming_Sub arming;
|
2017-02-27 17:12:56 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Altitude
|
|
|
|
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
|
|
|
int16_t climb_rate;
|
2016-05-22 21:50:44 -03:00
|
|
|
float target_rangefinder_alt; // desired altitude in cm above the ground
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2016-07-03 21:29:34 -03:00
|
|
|
// Turn counter
|
|
|
|
int32_t quarter_turn_count;
|
|
|
|
uint8_t last_turn_state;
|
|
|
|
|
2017-05-08 20:37:42 -03:00
|
|
|
// Input gain
|
|
|
|
float gain;
|
|
|
|
|
|
|
|
// Flag indicating if we are currently using input hold
|
|
|
|
bool input_hold_engaged;
|
|
|
|
|
2020-02-20 14:40:01 -04:00
|
|
|
// Flag indicating if we are currently controlling Pitch and Roll instead of forward/lateral
|
|
|
|
bool roll_pitch_flag = false;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// 3D Location vectors
|
2016-01-14 15:30:56 -04:00
|
|
|
// Current location of the Sub (altitude is relative to home)
|
2019-01-02 00:40:53 -04:00
|
|
|
Location current_loc;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Navigation Yaw control
|
|
|
|
// auto flight mode's yaw mode
|
|
|
|
uint8_t auto_yaw_mode;
|
|
|
|
|
|
|
|
// Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI
|
|
|
|
Vector3f roi_WP;
|
|
|
|
|
|
|
|
// bearing from current location to the yaw_look_at_WP
|
|
|
|
float yaw_look_at_WP_bearing;
|
|
|
|
|
2017-02-07 20:42:28 -04:00
|
|
|
float yaw_xtrack_correct_heading;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// yaw used for YAW_LOOK_AT_HEADING yaw_mode
|
|
|
|
int32_t yaw_look_at_heading;
|
|
|
|
|
|
|
|
// Deg/s we should turn
|
|
|
|
int16_t yaw_look_at_heading_slew;
|
|
|
|
|
|
|
|
// heading when in yaw_look_ahead_bearing
|
|
|
|
float yaw_look_ahead_bearing;
|
|
|
|
|
|
|
|
// Delay Mission Scripting Command
|
|
|
|
int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
|
|
|
|
uint32_t condition_start;
|
|
|
|
|
|
|
|
// Inertial Navigation
|
2021-10-18 23:15:01 -03:00
|
|
|
AP_InertialNav inertial_nav;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-20 14:30:35 -04:00
|
|
|
AP_AHRS_View ahrs_view;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Attitude, Position and Waypoint navigation objects
|
|
|
|
// To-Do: move inertial nav up or other navigation variables down here
|
2017-02-02 23:17:44 -04:00
|
|
|
AC_AttitudeControl_Sub attitude_control;
|
2016-02-23 02:15:15 -04:00
|
|
|
|
2022-07-03 15:57:24 -03:00
|
|
|
AC_PosControl pos_control;
|
2016-12-04 12:49:46 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
AC_WPNav wp_nav;
|
2018-03-28 01:54:24 -03:00
|
|
|
AC_Loiter loiter_nav;
|
2015-12-30 18:57:56 -04:00
|
|
|
AC_Circle circle_nav;
|
|
|
|
|
2017-08-29 15:49:08 -03:00
|
|
|
// Camera
|
2022-06-02 05:28:26 -03:00
|
|
|
#if AP_CAMERA_ENABLED
|
2019-03-26 08:07:53 -03:00
|
|
|
AP_Camera camera{MASK_LOG_CAMERA};
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// Camera/Antenna mount tracking and stabilisation stuff
|
2020-07-24 14:30:21 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2019-03-26 08:37:12 -03:00
|
|
|
AP_Mount camera_mount;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2017-08-29 20:37:43 -03:00
|
|
|
#if AVOIDANCE_ENABLED == ENABLED
|
2019-05-22 03:44:51 -03:00
|
|
|
AC_Avoid avoid;
|
2017-08-29 20:37:43 -03:00
|
|
|
#endif
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Rally library
|
2022-09-21 10:13:20 -03:00
|
|
|
#if HAL_RALLY_ENABLED
|
2019-02-18 05:38:56 -04:00
|
|
|
AP_Rally rally;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// terrain handling
|
2021-02-12 23:40:10 -04:00
|
|
|
#if AP_TERRAIN_AVAILABLE
|
2022-02-01 23:28:34 -04:00
|
|
|
AP_Terrain terrain;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2018-04-14 00:15:15 -03:00
|
|
|
// used to allow attitude and depth control without a position system
|
|
|
|
struct attitude_no_gps_struct {
|
|
|
|
uint32_t last_message_ms;
|
|
|
|
mavlink_set_attitude_target_t packet;
|
|
|
|
};
|
|
|
|
|
|
|
|
attitude_no_gps_struct set_attitude_target_no_gps {0};
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// Top-level logic
|
|
|
|
// setup the var_info table
|
|
|
|
AP_Param param_loader;
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
uint32_t last_pilot_heading;
|
|
|
|
uint32_t last_pilot_yaw_input_ms;
|
2018-10-07 21:45:00 -03:00
|
|
|
uint32_t fs_terrain_recover_start_ms;
|
2016-09-05 14:21:46 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
static const AP_Scheduler::Task scheduler_tasks[];
|
|
|
|
static const AP_Param::Info var_info[];
|
|
|
|
static const struct LogStructure log_structure[];
|
|
|
|
|
2022-04-20 13:07:42 -03:00
|
|
|
void run_rate_controller();
|
2017-03-09 13:50:58 -04:00
|
|
|
void fifty_hz_loop();
|
2015-12-30 18:57:56 -04:00
|
|
|
void update_batt_compass(void);
|
|
|
|
void ten_hz_logging_loop();
|
2017-02-03 00:18:27 -04:00
|
|
|
void twentyfive_hz_logging();
|
2015-12-30 18:57:56 -04:00
|
|
|
void three_hz_loop();
|
|
|
|
void one_hz_loop();
|
2016-07-03 21:29:34 -03:00
|
|
|
void update_turn_counter();
|
2015-12-30 18:57:56 -04:00
|
|
|
void read_AHRS(void);
|
|
|
|
void update_altitude();
|
|
|
|
float get_smoothing_gain();
|
|
|
|
void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
|
2021-02-01 12:26:24 -04:00
|
|
|
float get_pilot_desired_yaw_rate(int16_t stick_angle) const;
|
2015-12-30 18:57:56 -04:00
|
|
|
void check_ekf_yaw_reset();
|
|
|
|
float get_roi_yaw();
|
|
|
|
float get_look_ahead_yaw();
|
|
|
|
float get_pilot_desired_climb_rate(float throttle_control);
|
|
|
|
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
|
|
|
|
void rotate_body_frame_to_NE(float &x, float &y);
|
|
|
|
void Log_Write_Control_Tuning();
|
|
|
|
void Log_Write_Attitude();
|
2019-10-25 03:07:45 -03:00
|
|
|
void Log_Write_Data(LogDataID id, int32_t value);
|
|
|
|
void Log_Write_Data(LogDataID id, uint32_t value);
|
|
|
|
void Log_Write_Data(LogDataID id, int16_t value);
|
|
|
|
void Log_Write_Data(LogDataID id, uint16_t value);
|
|
|
|
void Log_Write_Data(LogDataID id, float value);
|
2016-05-03 01:45:37 -03:00
|
|
|
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
|
2015-12-30 18:57:56 -04:00
|
|
|
void Log_Write_Vehicle_Startup_Messages();
|
2020-01-16 06:40:53 -04:00
|
|
|
void load_parameters(void) override;
|
2015-12-30 18:57:56 -04:00
|
|
|
void userhook_init();
|
|
|
|
void userhook_FastLoop();
|
|
|
|
void userhook_50Hz();
|
|
|
|
void userhook_MediumLoop();
|
|
|
|
void userhook_SlowLoop();
|
|
|
|
void userhook_SuperSlowLoop();
|
|
|
|
void update_home_from_EKF();
|
|
|
|
void set_home_to_current_location_inflight();
|
2018-05-29 21:47:13 -03:00
|
|
|
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
|
|
|
|
bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
|
2015-12-30 18:57:56 -04:00
|
|
|
bool far_from_EKF_origin(const Location& loc);
|
|
|
|
void exit_mission();
|
|
|
|
bool verify_loiter_unlimited();
|
|
|
|
bool verify_loiter_time();
|
|
|
|
bool verify_wait_delay();
|
|
|
|
bool verify_within_distance();
|
|
|
|
bool verify_yaw();
|
2017-04-14 16:10:29 -03:00
|
|
|
bool acro_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void acro_run();
|
|
|
|
void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
|
2017-04-14 16:10:29 -03:00
|
|
|
bool althold_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void althold_run();
|
2017-04-14 16:10:29 -03:00
|
|
|
bool auto_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void auto_run();
|
|
|
|
void auto_wp_start(const Vector3f& destination);
|
2019-01-02 00:40:53 -04:00
|
|
|
void auto_wp_start(const Location& dest_loc);
|
2015-12-30 18:57:56 -04:00
|
|
|
void auto_wp_run();
|
2023-02-14 18:17:46 -04:00
|
|
|
void auto_circle_movetoedge_start(const Location &circle_center, float radius_m, bool ccw_turn);
|
2015-12-30 18:57:56 -04:00
|
|
|
void auto_circle_start();
|
|
|
|
void auto_circle_run();
|
|
|
|
void auto_nav_guided_start();
|
|
|
|
void auto_nav_guided_run();
|
|
|
|
bool auto_loiter_start();
|
|
|
|
void auto_loiter_run();
|
2021-02-01 12:26:24 -04:00
|
|
|
uint8_t get_default_auto_yaw_mode(bool rtl) const;
|
2015-12-30 18:57:56 -04:00
|
|
|
void set_auto_yaw_mode(uint8_t yaw_mode);
|
|
|
|
void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle);
|
|
|
|
void set_auto_yaw_roi(const Location &roi_location);
|
|
|
|
float get_auto_heading(void);
|
2017-04-14 16:10:29 -03:00
|
|
|
bool circle_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void circle_run();
|
2017-04-14 16:10:29 -03:00
|
|
|
bool guided_init(bool ignore_checks = false);
|
2015-12-30 18:57:56 -04:00
|
|
|
void guided_pos_control_start();
|
|
|
|
void guided_vel_control_start();
|
|
|
|
void guided_posvel_control_start();
|
|
|
|
void guided_angle_control_start();
|
2016-05-22 21:50:44 -03:00
|
|
|
bool guided_set_destination(const Vector3f& destination);
|
2019-01-02 00:40:53 -04:00
|
|
|
bool guided_set_destination(const Location& dest_loc);
|
2015-12-30 18:57:56 -04:00
|
|
|
void guided_set_velocity(const Vector3f& velocity);
|
2017-12-03 13:12:38 -04:00
|
|
|
bool guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity);
|
2015-12-30 18:57:56 -04:00
|
|
|
void guided_set_angle(const Quaternion &q, float climb_rate_cms);
|
|
|
|
void guided_run();
|
|
|
|
void guided_pos_control_run();
|
|
|
|
void guided_vel_control_run();
|
|
|
|
void guided_posvel_control_run();
|
|
|
|
void guided_angle_control_run();
|
|
|
|
void guided_limit_clear();
|
|
|
|
void guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm);
|
|
|
|
void guided_limit_init_time_and_pos();
|
|
|
|
bool guided_limit_check();
|
2017-03-23 01:21:41 -03:00
|
|
|
|
2017-04-14 16:10:29 -03:00
|
|
|
bool poshold_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void poshold_run();
|
|
|
|
|
2019-09-23 13:41:30 -03:00
|
|
|
bool motordetect_init();
|
|
|
|
void motordetect_run();
|
|
|
|
|
2017-04-14 16:10:29 -03:00
|
|
|
bool stabilize_init(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void stabilize_run();
|
2020-08-03 00:31:50 -03:00
|
|
|
void control_depth();
|
2017-04-14 16:10:29 -03:00
|
|
|
bool manual_init(void);
|
2016-06-26 01:07:27 -03:00
|
|
|
void manual_run();
|
2017-04-15 02:03:56 -03:00
|
|
|
void failsafe_sensors_check(void);
|
2017-03-24 17:30:28 -03:00
|
|
|
void failsafe_crash_check();
|
2017-04-08 11:36:16 -03:00
|
|
|
void failsafe_ekf_check(void);
|
2018-03-01 14:44:02 -04:00
|
|
|
void handle_battery_failsafe(const char* type_str, const int8_t action);
|
2015-12-30 18:57:56 -04:00
|
|
|
void failsafe_gcs_check();
|
2017-04-14 16:58:54 -03:00
|
|
|
void failsafe_pilot_input_check(void);
|
2017-01-30 13:49:39 -04:00
|
|
|
void set_neutral_controls(void);
|
2016-05-03 01:45:37 -03:00
|
|
|
void failsafe_terrain_check();
|
|
|
|
void failsafe_terrain_set_status(bool data_ok);
|
|
|
|
void failsafe_terrain_on_event();
|
2017-04-06 18:58:26 -03:00
|
|
|
void mainloop_failsafe_enable();
|
|
|
|
void mainloop_failsafe_disable();
|
2015-12-30 18:57:56 -04:00
|
|
|
void fence_check();
|
2019-10-17 00:50:07 -03:00
|
|
|
bool set_mode(control_mode_t mode, ModeReason reason);
|
|
|
|
bool set_mode(const uint8_t mode, const ModeReason reason) override;
|
2020-01-09 10:48:30 -04:00
|
|
|
uint8_t get_mode() const override { return (uint8_t)control_mode; }
|
2015-12-30 18:57:56 -04:00
|
|
|
void update_flight_mode();
|
2016-04-18 01:38:21 -03:00
|
|
|
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
|
|
|
|
bool mode_requires_GPS(control_mode_t mode);
|
|
|
|
bool mode_has_manual_throttle(control_mode_t mode);
|
|
|
|
bool mode_allows_arming(control_mode_t mode, bool arming_from_gcs);
|
|
|
|
void notify_flight_mode(control_mode_t mode);
|
2015-12-30 18:57:56 -04:00
|
|
|
void read_inertia();
|
2016-02-24 18:18:48 -04:00
|
|
|
void update_surface_and_bottom_detector();
|
|
|
|
void set_surfaced(bool at_surface);
|
|
|
|
void set_bottomed(bool at_bottom);
|
2015-12-30 18:57:56 -04:00
|
|
|
void motors_output();
|
|
|
|
void init_rc_in();
|
|
|
|
void init_rc_out();
|
|
|
|
void enable_motor_output();
|
2016-11-23 17:22:30 -04:00
|
|
|
void init_joystick();
|
2016-01-10 20:23:03 -04:00
|
|
|
void transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons);
|
2016-08-10 16:07:37 -03:00
|
|
|
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
|
2017-11-22 17:01:06 -04:00
|
|
|
void handle_jsbutton_release(uint8_t button, bool shift);
|
2016-03-12 14:14:40 -04:00
|
|
|
JSButton* get_button(uint8_t index);
|
2016-12-08 16:36:10 -04:00
|
|
|
void default_js_buttons(void);
|
2017-09-18 15:42:53 -03:00
|
|
|
void clear_input_hold();
|
2015-12-30 18:57:56 -04:00
|
|
|
void read_barometer(void);
|
2016-05-22 21:50:44 -03:00
|
|
|
void init_rangefinder(void);
|
|
|
|
void read_rangefinder(void);
|
2021-02-01 12:26:24 -04:00
|
|
|
bool rangefinder_alt_ok(void) const;
|
2016-05-03 01:45:37 -03:00
|
|
|
void terrain_update();
|
|
|
|
void terrain_logging();
|
2020-01-16 06:31:00 -04:00
|
|
|
void init_ardupilot() override;
|
|
|
|
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
|
|
|
uint8_t &task_count,
|
|
|
|
uint32_t &log_bit) override;
|
2015-12-30 18:57:56 -04:00
|
|
|
void startup_INS_ground();
|
|
|
|
bool position_ok();
|
|
|
|
bool ekf_position_ok();
|
|
|
|
bool optflow_position_ok();
|
|
|
|
bool should_log(uint32_t mask);
|
|
|
|
bool start_command(const AP_Mission::Mission_Command& cmd);
|
|
|
|
bool verify_command(const AP_Mission::Mission_Command& cmd);
|
|
|
|
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
|
|
|
|
|
|
|
bool do_guided(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_nav_wp(const AP_Mission::Mission_Command& cmd);
|
2017-03-08 22:59:39 -04:00
|
|
|
void do_surface(const AP_Mission::Mission_Command& cmd);
|
2017-03-11 12:06:03 -04:00
|
|
|
void do_RTL(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_circle(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_loiter_time(const AP_Mission::Mission_Command& cmd);
|
|
|
|
#if NAV_GUIDED == ENABLED
|
|
|
|
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_guided_limits(const AP_Mission::Mission_Command& cmd);
|
|
|
|
#endif
|
2016-05-22 21:50:44 -03:00
|
|
|
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
|
2015-12-30 18:57:56 -04:00
|
|
|
void do_wait_delay(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_within_distance(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_yaw(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_change_speed(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_set_home(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_roi(const AP_Mission::Mission_Command& cmd);
|
|
|
|
void do_mount_control(const AP_Mission::Mission_Command& cmd);
|
2017-04-13 00:15:51 -03:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
|
2017-03-08 22:59:39 -04:00
|
|
|
bool verify_surface(const AP_Mission::Mission_Command& cmd);
|
2017-03-11 12:06:03 -04:00
|
|
|
bool verify_RTL(void);
|
2015-12-30 18:57:56 -04:00
|
|
|
bool verify_circle(const AP_Mission::Mission_Command& cmd);
|
|
|
|
#if NAV_GUIDED == ENABLED
|
|
|
|
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
|
|
|
|
#endif
|
2016-05-22 21:50:44 -03:00
|
|
|
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
void log_init(void);
|
|
|
|
|
2017-03-24 15:37:45 -03:00
|
|
|
void failsafe_leak_check();
|
2016-09-03 19:17:34 -03:00
|
|
|
void failsafe_internal_pressure_check();
|
|
|
|
void failsafe_internal_temperature_check();
|
2016-08-19 14:54:22 -03:00
|
|
|
|
2017-02-07 20:42:28 -04:00
|
|
|
void failsafe_terrain_act(void);
|
|
|
|
bool auto_terrain_recover_start(void);
|
|
|
|
void auto_terrain_recover_run(void);
|
|
|
|
|
|
|
|
void translate_wpnav_rp(float &lateral_out, float &forward_out);
|
2017-03-04 15:41:26 -04:00
|
|
|
void translate_circle_nav_rp(float &lateral_out, float &forward_out);
|
2017-03-06 22:29:03 -04:00
|
|
|
void translate_pos_control_rp(float &lateral_out, float &forward_out);
|
2017-02-07 20:42:28 -04:00
|
|
|
|
2017-04-14 16:10:29 -03:00
|
|
|
bool surface_init(void);
|
2016-08-25 00:08:30 -03:00
|
|
|
void surface_run();
|
|
|
|
|
2021-02-01 12:26:24 -04:00
|
|
|
uint16_t get_pilot_speed_dn() const;
|
2017-11-19 08:29:09 -04:00
|
|
|
|
2017-01-31 13:06:55 -04:00
|
|
|
void convert_old_parameters(void);
|
2018-04-19 16:12:42 -03:00
|
|
|
bool handle_do_motor_test(mavlink_command_long_t command);
|
|
|
|
bool init_motor_test();
|
|
|
|
bool verify_motor_test();
|
|
|
|
|
|
|
|
uint32_t last_do_motor_test_fail_ms = 0;
|
|
|
|
uint32_t last_do_motor_test_ms = 0;
|
2017-01-31 13:06:55 -04:00
|
|
|
|
2018-04-14 00:16:57 -03:00
|
|
|
bool control_check_barometer();
|
|
|
|
|
2020-12-06 08:38:12 -04:00
|
|
|
// vehicle specific waypoint info helpers
|
|
|
|
bool get_wp_distance_m(float &distance) const override;
|
|
|
|
bool get_wp_bearing_deg(float &bearing) const override;
|
|
|
|
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
|
|
|
|
|
2018-03-01 14:44:02 -04:00
|
|
|
enum Failsafe_Action {
|
|
|
|
Failsafe_Action_None = 0,
|
|
|
|
Failsafe_Action_Warn = 1,
|
|
|
|
Failsafe_Action_Disarm = 2,
|
|
|
|
Failsafe_Action_Surface = 3
|
|
|
|
};
|
|
|
|
|
|
|
|
static constexpr int8_t _failsafe_priorities[] = {
|
|
|
|
Failsafe_Action_Disarm,
|
|
|
|
Failsafe_Action_Surface,
|
|
|
|
Failsafe_Action_Warn,
|
|
|
|
Failsafe_Action_None,
|
|
|
|
-1 // the priority list must end with a sentinel of -1
|
|
|
|
};
|
|
|
|
|
|
|
|
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
|
|
|
|
"_failsafe_priorities is missing the sentinel");
|
|
|
|
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
public:
|
2017-04-06 18:58:26 -03:00
|
|
|
void mainloop_failsafe_check();
|
2015-12-30 18:57:56 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2016-01-14 15:30:56 -04:00
|
|
|
extern Sub sub;
|