#pragma once
#include <cmath>
#include <stdio.h>
#include <stdarg.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_AccelCal/AP_AccelCal.h>
#include <AP_Math/AP_Math.h>
#include <AP_Declination/AP_Declination.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Mission/AP_Mission.h>
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h>
#include <AC_AttitudeControl/AC_PosControl.h>
#include <AP_Motors/AP_Motors.h>
#include <Filter/Filter.h>
#include <AP_Relay/AP_Relay.h>
#include <AP_Mount/AP_Mount.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_InertialNav/AP_InertialNav.h>
#include <AC_WPNav/AC_WPNav.h>
#include <AC_WPNav/AC_Loiter.h>
#include <AC_WPNav/AC_Circle.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_Scheduler/PerfInfo.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_JSButton/AP_JSButton.h>
#include <AP_LeakDetector/AP_LeakDetector.h>
#include <AP_Proximity/AP_Proximity.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_OSD/AP_OSD.h>
#include "defines.h"
#include "config.h"
#include "GCS_MAVLink_Sub.h"
#include "RC_Channel_Sub.h"
#include "Parameters.h"
#include "AP_Arming_Sub.h"
#include "GCS_Sub.h"
#include "mode.h"
#include "script_button.h"
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#if RCMAP_ENABLED
#include <AP_RCMapper/AP_RCMapper.h>
#endif
#include <AP_RPM/AP_RPM_config.h>
#if AP_RPM_ENABLED
#include <AP_RPM/AP_RPM.h>
#endif
#if AVOIDANCE_ENABLED
#include <AC_Avoidance/AC_Avoid.h>
#endif
#include <AP_Camera/AP_Camera.h>
#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
#endif
class Sub : public AP_Vehicle {
public:
friend class GCS_MAVLINK_Sub;
friend class GCS_Sub;
friend class Parameters;
friend class ParametersG2;
friend class AP_Arming_Sub;
friend class RC_Channels_Sub;
friend class RC_Channel_Sub;
friend class Mode;
friend class ModeManual;
friend class ModeStabilize;
friend class ModeAcro;
friend class ModeAlthold;
friend class ModeSurftrak;
friend class ModeGuided;
friend class ModePoshold;
friend class ModeAuto;
friend class ModeCircle;
friend class ModeSurface;
friend class ModeMotordetect;
Sub(void);
protected:
bool should_zero_rc_outputs_on_reboot() const override { return true; }
private:
Parameters g;
ParametersG2 g2;
RC_Channel *channel_roll;
RC_Channel *channel_pitch;
RC_Channel *channel_throttle;
RC_Channel *channel_yaw;
RC_Channel *channel_forward;
RC_Channel *channel_lateral;
#if AP_SUB_RC_ENABLED
AP_Int8 *flight_modes;
const uint8_t num_flight_modes = 6;
#endif
AP_LeakDetector leak_detector;
struct {
bool enabled;
bool alt_healthy;
float alt;
float min;
float max;
uint32_t last_healthy_ms;
float inertial_alt_cm;
float rangefinder_terrain_offset_cm;
LowPassFilterFloat alt_filt;
} rangefinder_state = { false, false, 0, 0, 0, 0, 0, 0 };
AP_Mission mission{
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 &),
FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};
#if AP_OPTICALFLOW_ENABLED
AP_OpticalFlow optflow;
#endif
#if OSD_ENABLED || OSD_PARAM_ENABLED
AP_OSD osd;
#endif
uint32_t ekfYawReset_ms = 0;
GCS_Sub _gcs;
GCS_Sub &gcs() { return _gcs; }
#ifdef USERHOOK_VARIABLES
# include USERHOOK_VARIABLES
#endif
union {
struct {
uint8_t pre_arm_check : 1;
uint8_t logging_started : 1;
uint8_t compass_mot : 1;
uint8_t motor_test : 1;
uint8_t initialised : 1;
uint8_t gps_base_pos_set : 1;
uint8_t at_bottom : 1;
uint8_t at_surface : 1;
uint8_t depth_sensor_present: 1;
uint8_t unused1 : 1;
};
uint32_t value;
} ap;
Mode::Number control_mode;
Mode::Number prev_control_mode;
#if RCMAP_ENABLED
RCMapper rcmap;
#endif
struct {
uint32_t last_leak_warn_ms;
uint32_t last_gcs_warn_ms;
uint32_t last_pilot_input_ms;
uint32_t terrain_first_failure_ms;
uint32_t terrain_last_failure_ms;
uint32_t last_crash_warn_ms;
uint32_t last_ekf_warn_ms;
#if AP_SUB_RC_ENABLED
int8_t radio_counter;
uint8_t radio : 1;
#endif
uint8_t pilot_input : 1;
uint8_t gcs : 1;
uint8_t ekf : 1;
uint8_t terrain : 1;
uint8_t leak : 1;
uint8_t internal_pressure : 1;
uint8_t internal_temperature : 1;
uint8_t crash : 1;
uint8_t sensor_health : 1;
} failsafe;
bool any_failsafe_triggered() const {
return (
failsafe.pilot_input
|| battery.has_failsafed()
|| failsafe.gcs
|| failsafe.ekf
|| failsafe.terrain
|| failsafe.leak
|| failsafe.internal_pressure
|| failsafe.internal_temperature
|| failsafe.crash
|| failsafe.sensor_health
);
}
struct {
uint8_t depth : 1;
uint8_t compass : 1;
} sensor_health;
uint8_t depth_sensor_idx;
AP_Motors6DOF motors;
bool circle_pilot_yaw_override;
int32_t initial_armed_bearing;
uint16_t loiter_time_max;
uint32_t loiter_time;
uint32_t nav_delay_time_max_ms;
uint32_t nav_delay_time_start_ms;
AP_BattMonitor battery{MASK_LOG_CURRENT,
FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),
_failsafe_priorities};
AP_Arming_Sub arming;
int16_t climb_rate;
int32_t quarter_turn_count;
uint8_t last_turn_state;
float gain;
bool input_hold_engaged;
bool roll_pitch_flag = false;
Location current_loc;
uint8_t auto_yaw_mode;
bool yaw_rate_only;
Vector3f roi_WP;
float yaw_look_at_WP_bearing;
float yaw_xtrack_correct_heading;
int32_t yaw_look_at_heading;
int16_t yaw_look_at_heading_slew;
float yaw_look_ahead_bearing;
int32_t condition_value;
uint32_t condition_start;
AP_InertialNav inertial_nav;
AP_AHRS_View ahrs_view;
AC_AttitudeControl_Sub attitude_control;
AC_PosControl pos_control;
AC_WPNav wp_nav;
AC_Loiter loiter_nav;
AC_Circle circle_nav;
#if AP_CAMERA_ENABLED
AP_Camera camera{MASK_LOG_CAMERA};
#endif
#if HAL_MOUNT_ENABLED
AP_Mount camera_mount;
#endif
#if AVOIDANCE_ENABLED
AC_Avoid avoid;
#endif
#if HAL_RALLY_ENABLED
AP_Rally rally;
#endif
#if AP_TERRAIN_AVAILABLE
AP_Terrain terrain;
#endif
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};
AP_Param param_loader;
float last_pilot_heading_rad;
uint32_t last_pilot_yaw_input_ms;
uint32_t fs_terrain_recover_start_ms;
static const AP_Scheduler::Task scheduler_tasks[];
static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[];
void run_rate_controller();
void fifty_hz_loop();
void update_batt_compass(void);
void ten_hz_logging_loop();
void twentyfive_hz_logging();
void loop_rate_logging();
void three_hz_loop();
void one_hz_loop();
void update_turn_counter();
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);
float get_pilot_desired_yaw_rate(int16_t stick_angle) const;
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_pilot_desired_horizontal_rate(RC_Channel *channel) const;
void rotate_body_frame_to_NE(float &x, float &y);
#if HAL_LOGGING_ENABLED
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
const struct LogStructure *get_log_structures() const override {
return log_structure;
}
uint8_t get_num_log_structures() const override;
void Log_Write_Control_Tuning();
void Log_Write_Attitude();
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);
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
void Log_Write_Vehicle_Startup_Messages();
#endif
void load_parameters(void) override;
void userhook_init();
void userhook_FastLoop();
void userhook_50Hz();
void userhook_MediumLoop();
void userhook_SlowLoop();
void userhook_SuperSlowLoop();
void update_home_from_EKF();
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
float get_alt_rel() const WARN_IF_UNUSED;
float get_alt_msl() const WARN_IF_UNUSED;
void exit_mission();
void set_origin(const Location& loc);
bool verify_loiter_unlimited();
bool verify_loiter_time();
bool verify_wait_delay();
bool verify_within_distance();
bool verify_yaw();
void failsafe_sensors_check(void);
void failsafe_crash_check();
void failsafe_ekf_check(void);
void handle_battery_failsafe(const char* type_str, const int8_t action);
void failsafe_gcs_check();
void failsafe_pilot_input_check(void);
void set_neutral_controls(void);
void failsafe_terrain_check();
void failsafe_terrain_set_status(bool data_ok);
void failsafe_terrain_on_event();
void mainloop_failsafe_enable();
void mainloop_failsafe_disable();
#if AP_FENCE_ENABLED
void fence_check();
void fence_checks_async() override;
#endif
bool set_mode(Mode::Number mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
uint8_t get_mode() const override { return (uint8_t)control_mode; }
void update_flight_mode();
void exit_mode(Mode::Number old_control_mode, Mode::Number new_control_mode);
void notify_flight_mode();
void read_inertia();
void update_surface_and_bottom_detector();
void set_surfaced(bool at_surface);
void set_bottomed(bool at_bottom);
void motors_output();
void init_rc_in();
void init_rc_out();
#if AP_SUB_RC_ENABLED
void rc_loop();
void read_radio();
uint32_t last_radio_update_ms;
void set_failsafe_radio(bool b);
void set_throttle_and_failsafe(uint16_t throttle_pwm);
void failsafe_radio_off_event();
void failsafe_radio_on_event();
#endif
void enable_motor_output();
void init_joystick();
void transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions,
int16_t s,
int16_t t,
int16_t aux1,
int16_t aux2,
int16_t aux3,
int16_t aux4,
int16_t aux5,
int16_t aux6);
void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
void handle_jsbutton_release(uint8_t button, bool shift);
JSButton* get_button(uint8_t index);
void default_js_buttons(void);
void clear_input_hold();
void read_barometer(void);
void init_rangefinder(void);
void read_rangefinder(void);
void terrain_update();
void terrain_logging();
void init_ardupilot() override;
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
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);
void do_surface(const AP_Mission::Mission_Command& cmd);
void do_RTL(void);
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
void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
void do_guided_limits(const AP_Mission::Mission_Command& cmd);
#endif
void do_nav_delay(const AP_Mission::Mission_Command& cmd);
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);
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
bool verify_surface(const AP_Mission::Mission_Command& cmd);
bool verify_RTL(void);
bool verify_circle(const AP_Mission::Mission_Command& cmd);
#if NAV_GUIDED
bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
#endif
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
void failsafe_leak_check();
void failsafe_internal_pressure_check();
void failsafe_internal_temperature_check();
void failsafe_terrain_act(void);
void translate_wpnav_rp(float &lateral_out, float &forward_out);
void translate_circle_nav_rp(float &lateral_out, float &forward_out);
void translate_pos_control_rp(float &lateral_out, float &forward_out);
void stats_update();
uint16_t get_pilot_speed_dn() const;
void convert_old_parameters(void);
#if LEAKDETECTOR_MAX_INSTANCES > 0
void update_leak_pins();
#endif
#if AP_RELAY_ENABLED
void update_relay_pins();
#endif
bool handle_do_motor_test(mavlink_command_int_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;
bool control_check_barometer();
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;
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
};
static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
"_failsafe_priorities is missing the sentinel");
Mode *mode_from_mode_num(const Mode::Number num);
void exit_mode(Mode *&old_flightmode, Mode *&new_flightmode);
Mode *flightmode;
ModeManual mode_manual;
ModeStabilize mode_stabilize;
ModeAcro mode_acro;
ModeAlthold mode_althold;
ModeAuto mode_auto;
ModeGuided mode_guided;
ModePoshold mode_poshold;
ModeCircle mode_circle;
ModeSurface mode_surface;
ModeMotordetect mode_motordetect;
ModeSurftrak mode_surftrak;
AutoSubMode auto_mode;
GuidedSubMode guided_mode;
#if AP_SCRIPTING_ENABLED
ScriptButton script_buttons[4];
#endif
public:
void mainloop_failsafe_check();
bool rangefinder_alt_ok() const WARN_IF_UNUSED;
static Sub *_singleton;
static Sub *get_singleton() {
return _singleton;
}
#if AP_SCRIPTING_ENABLED
bool is_button_pressed(uint8_t index);
uint8_t get_and_clear_button_count(uint8_t index);
#if AP_RANGEFINDER_ENABLED
float get_rangefinder_target_cm() const WARN_IF_UNUSED { return mode_surftrak.get_rangefinder_target_cm(); }
bool set_rangefinder_target_cm(float new_target_cm) { return mode_surftrak.set_rangefinder_target_cm(new_target_cm); }
#endif
#endif
};
extern const AP_HAL::HAL& hal;
extern Sub sub;