2013-09-12 22:43:59 -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-02-17 21:25:52 -04:00
|
|
|
#pragma once
|
|
|
|
|
2013-09-12 22:43:59 -03:00
|
|
|
/*
|
|
|
|
this header holds a parameter structure for each vehicle type for
|
|
|
|
parameters needed by multiple libraries
|
|
|
|
*/
|
|
|
|
|
2019-10-17 00:47:11 -03:00
|
|
|
#include "ModeReason.h" // reasons can't be defined in this header due to circular loops
|
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
|
2020-06-24 09:08:02 -03:00
|
|
|
#include <AP_CANManager/AP_CANManager.h>
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_Button/AP_Button.h>
|
2021-10-21 03:37:35 -03:00
|
|
|
#include <AP_EFI/AP_EFI.h>
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2020-10-22 14:17:26 -03:00
|
|
|
#include <AP_Generator/AP_Generator.h>
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
|
|
|
#include <AP_Notify/AP_Notify.h> // Notify library
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2019-11-26 02:46:05 -04:00
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_Relay/AP_Relay.h> // APM relay
|
|
|
|
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
|
2019-12-18 18:35:32 -04:00
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
2018-12-27 02:31:34 -04:00
|
|
|
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
|
|
|
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
2019-12-18 18:35:32 -04:00
|
|
|
#include <AP_Camera/AP_RunCam.h>
|
2020-01-02 23:56:06 -04:00
|
|
|
#include <AP_Hott_Telem/AP_Hott_Telem.h>
|
2020-02-11 02:15:39 -04:00
|
|
|
#include <AP_ESC_Telem/AP_ESC_Telem.h>
|
2019-12-30 14:15:48 -04:00
|
|
|
#include <AP_GyroFFT/AP_GyroFFT.h>
|
2020-04-06 01:12:11 -03:00
|
|
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
2021-02-17 15:15:07 -04:00
|
|
|
#include <AP_VideoTX/AP_VideoTX.h>
|
2020-08-04 17:39:40 -03:00
|
|
|
#include <AP_MSP/AP_MSP.h>
|
2020-09-10 09:54:10 -03:00
|
|
|
#include <AP_Frsky_Telem/AP_Frsky_Parameters.h>
|
2020-12-27 22:06:14 -04:00
|
|
|
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
|
2021-01-29 15:55:49 -04:00
|
|
|
#include <AP_VideoTX/AP_SmartAudio.h>
|
2021-10-06 01:51:07 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
#include <SITL/SITL.h>
|
|
|
|
#endif
|
2014-03-25 22:15:45 -03:00
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
class AP_Vehicle : public AP_HAL::HAL::Callbacks {
|
2013-09-12 22:43:59 -03:00
|
|
|
|
|
|
|
public:
|
2018-12-27 02:31:34 -04:00
|
|
|
|
2019-10-08 19:36:46 -03:00
|
|
|
AP_Vehicle() {
|
|
|
|
if (_singleton) {
|
|
|
|
AP_HAL::panic("Too many Vehicles");
|
|
|
|
}
|
2019-12-18 18:35:32 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
2019-10-08 19:36:46 -03:00
|
|
|
_singleton = this;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
AP_Vehicle(const AP_Vehicle &other) = delete;
|
|
|
|
AP_Vehicle &operator=(const AP_Vehicle&) = delete;
|
|
|
|
|
|
|
|
static AP_Vehicle *get_singleton();
|
2018-12-27 02:31:34 -04:00
|
|
|
|
2020-01-16 06:31:20 -04:00
|
|
|
// setup() is called once during vehicle startup to initialise the
|
|
|
|
// vehicle object and the objects it contains. The
|
|
|
|
// AP_HAL_MAIN_CALLBACKS pragma creates a main(...) function
|
|
|
|
// referencing an object containing setup() and loop() functions.
|
|
|
|
// A vehicle is not expected to override setup(), but
|
|
|
|
// subclass-specific initialisation can be done in init_ardupilot
|
|
|
|
// which is called from setup().
|
|
|
|
void setup(void) override final;
|
|
|
|
|
2020-01-27 21:36:10 -04:00
|
|
|
// HAL::Callbacks implementation.
|
|
|
|
void loop() override final;
|
|
|
|
|
2021-02-02 19:48:14 -04:00
|
|
|
// set_mode *must* set control_mode_reason
|
2021-02-09 13:08:10 -04:00
|
|
|
virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) = 0;
|
|
|
|
virtual uint8_t get_mode() const = 0;
|
2019-10-17 00:47:11 -03:00
|
|
|
|
2021-02-02 19:48:14 -04:00
|
|
|
ModeReason get_control_mode_reason() const {
|
|
|
|
return control_mode_reason;
|
|
|
|
}
|
|
|
|
|
2021-08-24 23:04:50 -03:00
|
|
|
// perform any notifications required to indicate a mode change
|
|
|
|
// failed due to a bad mode number being supplied. This can
|
|
|
|
// happen for many reasons - bad mavlink packet and bad mode
|
|
|
|
// parameters for example.
|
|
|
|
void notify_no_such_mode(uint8_t mode_number);
|
|
|
|
|
2013-09-12 22:43:59 -03:00
|
|
|
/*
|
|
|
|
common parameters for fixed wing aircraft
|
|
|
|
*/
|
|
|
|
struct FixedWing {
|
|
|
|
AP_Int8 throttle_min;
|
2021-02-01 12:26:35 -04:00
|
|
|
AP_Int8 throttle_max;
|
2013-09-12 22:43:59 -03:00
|
|
|
AP_Int8 throttle_slewrate;
|
|
|
|
AP_Int8 throttle_cruise;
|
2015-04-15 19:51:30 -03:00
|
|
|
AP_Int8 takeoff_throttle_max;
|
2016-08-07 21:48:12 -03:00
|
|
|
AP_Int16 airspeed_min;
|
|
|
|
AP_Int16 airspeed_max;
|
2016-11-17 21:07:10 -04:00
|
|
|
AP_Int32 airspeed_cruise_cm;
|
|
|
|
AP_Int32 min_gndspeed_cm;
|
|
|
|
AP_Int8 crash_detection_enable;
|
2016-06-23 09:39:59 -03:00
|
|
|
AP_Int16 roll_limit_cd;
|
2013-09-12 22:43:59 -03:00
|
|
|
AP_Int16 pitch_limit_max_cd;
|
2021-02-01 12:26:35 -04:00
|
|
|
AP_Int16 pitch_limit_min_cd;
|
2014-04-13 09:11:28 -03:00
|
|
|
AP_Int8 autotune_level;
|
2014-11-12 23:05:22 -04:00
|
|
|
AP_Int8 stall_prevention;
|
2017-01-15 16:20:09 -04:00
|
|
|
AP_Int16 loiter_radius;
|
2016-11-16 21:02:27 -04:00
|
|
|
|
|
|
|
struct Rangefinder_State {
|
|
|
|
bool in_range:1;
|
|
|
|
bool have_initial_reading:1;
|
|
|
|
bool in_use:1;
|
|
|
|
float initial_range;
|
|
|
|
float correction;
|
|
|
|
float initial_correction;
|
|
|
|
float last_stable_correction;
|
|
|
|
uint32_t last_correction_time_ms;
|
|
|
|
uint8_t in_range_count;
|
|
|
|
float height_estimate;
|
|
|
|
float last_distance;
|
|
|
|
};
|
2016-12-13 22:19:56 -04:00
|
|
|
|
|
|
|
|
|
|
|
// stages of flight
|
|
|
|
enum FlightStage {
|
|
|
|
FLIGHT_TAKEOFF = 1,
|
|
|
|
FLIGHT_VTOL = 2,
|
|
|
|
FLIGHT_NORMAL = 3,
|
2017-01-10 15:47:14 -04:00
|
|
|
FLIGHT_LAND = 4,
|
2016-12-13 23:18:48 -04:00
|
|
|
FLIGHT_ABORT_LAND = 7
|
2016-12-13 22:19:56 -04:00
|
|
|
};
|
2013-09-12 22:43:59 -03:00
|
|
|
};
|
2013-10-18 05:02:52 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
common parameters for multicopters
|
|
|
|
*/
|
|
|
|
struct MultiCopter {
|
|
|
|
AP_Int16 angle_max;
|
|
|
|
};
|
2018-12-27 02:31:34 -04:00
|
|
|
|
2019-12-18 18:35:32 -04:00
|
|
|
void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks);
|
2020-03-08 23:58:54 -03:00
|
|
|
// implementations *MUST* fill in all passed-in fields or we get
|
|
|
|
// Valgrind errors
|
2020-01-16 06:31:20 -04:00
|
|
|
virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0;
|
|
|
|
|
2020-01-06 18:38:12 -04:00
|
|
|
/*
|
|
|
|
set the "likely flying" flag. This is not guaranteed to be
|
|
|
|
accurate, but is the vehicle codes best guess as to the whether
|
|
|
|
the vehicle is currently flying
|
|
|
|
*/
|
|
|
|
void set_likely_flying(bool b) {
|
|
|
|
if (b && !likely_flying) {
|
|
|
|
_last_flying_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
likely_flying = b;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
get the likely flying status. Returns true if the vehicle code
|
|
|
|
thinks we are flying at the moment. Not guaranteed to be
|
|
|
|
accurate
|
|
|
|
*/
|
|
|
|
bool get_likely_flying(void) const {
|
|
|
|
return likely_flying;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return time in milliseconds since likely_flying was set
|
|
|
|
true. Returns zero if likely_flying is currently false
|
|
|
|
*/
|
|
|
|
uint32_t get_time_flying_ms(void) const {
|
|
|
|
if (!likely_flying) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return AP_HAL::millis() - _last_flying_ms;
|
|
|
|
}
|
|
|
|
|
2020-07-15 23:52:11 -03:00
|
|
|
// returns true if the vehicle has crashed
|
|
|
|
virtual bool is_crashed() const;
|
|
|
|
|
2021-11-15 01:08:32 -04:00
|
|
|
#if AP_SCRIPTING_ENABLED
|
2020-03-06 22:29:07 -04:00
|
|
|
/*
|
|
|
|
methods to control vehicle for use by scripting
|
|
|
|
*/
|
|
|
|
virtual bool start_takeoff(float alt) { return false; }
|
2020-02-18 00:10:56 -04:00
|
|
|
virtual bool set_target_location(const Location& target_loc) { return false; }
|
2021-08-11 08:24:13 -03:00
|
|
|
virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; }
|
2021-03-21 13:50:44 -03:00
|
|
|
virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
|
2021-08-11 08:24:13 -03:00
|
|
|
virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }
|
2020-03-06 22:29:07 -04:00
|
|
|
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; }
|
2021-08-11 08:24:13 -03:00
|
|
|
virtual bool set_target_velaccel_NED(const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }
|
2020-05-31 20:30:02 -03:00
|
|
|
virtual bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) { return false; }
|
|
|
|
|
2021-10-25 01:34:59 -03:00
|
|
|
// command throttle percentage and roll, pitch, yaw target
|
|
|
|
// rates. For use with scripting controllers
|
2022-02-07 16:29:39 -04:00
|
|
|
virtual void set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps) {}
|
2022-02-06 22:23:17 -04:00
|
|
|
virtual bool nav_scripting_enable(uint8_t mode) {return false;}
|
2021-10-25 01:34:59 -03:00
|
|
|
|
2020-03-06 06:10:51 -04:00
|
|
|
// get target location (for use by scripting)
|
|
|
|
virtual bool get_target_location(Location& target_loc) { return false; }
|
2020-05-31 20:30:02 -03:00
|
|
|
|
2021-08-24 08:11:13 -03:00
|
|
|
// circle mode controls (only used by scripting with Copter)
|
|
|
|
virtual bool get_circle_radius(float &radius_m) { return false; }
|
|
|
|
virtual bool set_circle_rate(float rate_dps) { return false; }
|
|
|
|
|
2020-06-15 04:33:57 -03:00
|
|
|
// set steering and throttle (-1 to +1) (for use by scripting with Rover)
|
|
|
|
virtual bool set_steering_and_throttle(float steering, float throttle) { return false; }
|
2021-10-25 01:34:59 -03:00
|
|
|
|
2022-01-16 06:09:10 -04:00
|
|
|
// set turn rate in deg/sec and speed in meters/sec (for use by scripting with Rover)
|
|
|
|
virtual bool set_desired_turn_rate_and_speed(float turn_rate, float speed) { return false; }
|
|
|
|
|
2021-10-25 01:34:59 -03:00
|
|
|
// support for NAV_SCRIPT_TIME mission command
|
|
|
|
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) { return false; }
|
|
|
|
virtual void nav_script_time_done(uint16_t id) {}
|
|
|
|
|
2020-06-15 04:33:57 -03:00
|
|
|
|
2020-08-07 20:04:16 -03:00
|
|
|
// control outputs enumeration
|
|
|
|
enum class ControlOutput {
|
|
|
|
Roll = 1,
|
|
|
|
Pitch = 2,
|
|
|
|
Throttle = 3,
|
|
|
|
Yaw = 4,
|
|
|
|
Lateral = 5,
|
|
|
|
MainSail = 6,
|
|
|
|
WingSail = 7,
|
2020-08-28 15:51:26 -03:00
|
|
|
Walking_Height = 8,
|
2020-08-07 20:04:16 -03:00
|
|
|
Last_ControlOutput // place new values before this
|
|
|
|
};
|
|
|
|
|
|
|
|
// get control output (for use in scripting)
|
|
|
|
// returns true on success and control_value is set to a value in the range -1 to +1
|
|
|
|
virtual bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) { return false; }
|
|
|
|
|
2021-12-12 21:24:49 -04:00
|
|
|
#endif // AP_SCRIPTING_ENABLED
|
|
|
|
|
2020-06-09 17:14:25 -03:00
|
|
|
// update the harmonic notch
|
|
|
|
virtual void update_dynamic_notch() {};
|
2020-09-27 22:21:52 -03:00
|
|
|
|
|
|
|
// zeroing the RC outputs can prevent unwanted motor movement:
|
|
|
|
virtual bool should_zero_rc_outputs_on_reboot() const { return false; }
|
|
|
|
|
|
|
|
// reboot the vehicle in an orderly manner, doing various cleanups
|
|
|
|
// and flashing LEDs as appropriate
|
|
|
|
void reboot(bool hold_in_bootloader);
|
|
|
|
|
2020-12-05 14:46:16 -04:00
|
|
|
/*
|
|
|
|
get the distance to next wp in meters
|
|
|
|
return false if failed or n/a
|
|
|
|
*/
|
|
|
|
virtual bool get_wp_distance_m(float &distance) const { return false; }
|
|
|
|
|
|
|
|
/*
|
|
|
|
get the current wp bearing in degrees
|
|
|
|
return false if failed or n/a
|
|
|
|
*/
|
|
|
|
virtual bool get_wp_bearing_deg(float &bearing) const { return false; }
|
|
|
|
|
|
|
|
/*
|
|
|
|
get the current wp crosstrack error in meters
|
|
|
|
return false if failed or n/a
|
|
|
|
*/
|
|
|
|
virtual bool get_wp_crosstrack_error_m(float &xtrack_error) const { return false; }
|
|
|
|
|
2020-09-10 09:54:10 -03:00
|
|
|
#if HAL_WITH_FRSKY_TELEM_BIDIRECTIONAL
|
|
|
|
AP_Frsky_Parameters frsky_parameters;
|
|
|
|
#endif
|
|
|
|
|
2021-06-14 13:05:03 -03:00
|
|
|
/*
|
|
|
|
Returns the pan and tilt for use by onvif camera in scripting
|
|
|
|
*/
|
|
|
|
virtual bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const { return false; }
|
|
|
|
|
2021-07-28 20:29:37 -03:00
|
|
|
#if OSD_ENABLED
|
|
|
|
// Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH_CD
|
|
|
|
virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const;
|
|
|
|
#endif
|
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
protected:
|
|
|
|
|
2020-01-16 06:31:20 -04:00
|
|
|
virtual void init_ardupilot() = 0;
|
2020-01-16 06:40:52 -04:00
|
|
|
virtual void load_parameters() = 0;
|
2020-02-11 21:01:17 -04:00
|
|
|
virtual void set_control_channels() {}
|
2020-01-16 06:31:20 -04:00
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
// board specific config
|
|
|
|
AP_BoardConfig BoardConfig;
|
|
|
|
|
2020-06-24 09:08:02 -03:00
|
|
|
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
2018-12-27 02:31:34 -04:00
|
|
|
// board specific config for CAN bus
|
2020-06-24 09:08:02 -03:00
|
|
|
AP_CANManager can_mgr;
|
2018-12-27 02:31:34 -04:00
|
|
|
#endif
|
|
|
|
|
2020-01-27 21:36:10 -04:00
|
|
|
// main loop scheduler
|
|
|
|
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)};
|
2020-03-07 06:49:59 -04:00
|
|
|
virtual void fast_loop();
|
2020-01-27 21:36:10 -04:00
|
|
|
|
|
|
|
// IMU variables
|
|
|
|
// Integration time; time last loop took to run
|
|
|
|
float G_Dt;
|
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
// sensor drivers
|
|
|
|
AP_GPS gps;
|
|
|
|
AP_Baro barometer;
|
|
|
|
Compass compass;
|
|
|
|
AP_InertialSensor ins;
|
2021-08-12 00:38:20 -03:00
|
|
|
#if HAL_BUTTON_ENABLED
|
2018-12-27 02:31:34 -04:00
|
|
|
AP_Button button;
|
2021-08-12 00:38:20 -03:00
|
|
|
#endif
|
2018-12-27 02:31:34 -04:00
|
|
|
RangeFinder rangefinder;
|
|
|
|
|
|
|
|
AP_RSSI rssi;
|
2019-12-18 18:35:32 -04:00
|
|
|
#if HAL_RUNCAM_ENABLED
|
|
|
|
AP_RunCam runcam;
|
|
|
|
#endif
|
2019-12-30 14:15:48 -04:00
|
|
|
#if HAL_GYROFFT_ENABLED
|
|
|
|
AP_GyroFFT gyro_fft;
|
|
|
|
#endif
|
2020-05-28 17:50:07 -03:00
|
|
|
AP_VideoTX vtx;
|
2018-12-27 02:31:34 -04:00
|
|
|
AP_SerialManager serial_manager;
|
|
|
|
|
|
|
|
AP_Relay relay;
|
|
|
|
|
|
|
|
AP_ServoRelayEvents ServoRelayEvents;
|
|
|
|
|
|
|
|
// notification object for LEDs, buzzers etc (parameter set to
|
|
|
|
// false disables external leds)
|
|
|
|
AP_Notify notify;
|
|
|
|
|
2019-11-24 19:15:14 -04:00
|
|
|
// Inertial Navigation EKF
|
2021-07-20 09:16:32 -03:00
|
|
|
AP_AHRS ahrs;
|
2019-11-24 19:15:14 -04:00
|
|
|
|
2020-01-02 23:56:06 -04:00
|
|
|
#if HAL_HOTT_TELEM_ENABLED
|
|
|
|
AP_Hott_Telem hott_telem;
|
|
|
|
#endif
|
|
|
|
|
2020-04-06 01:12:11 -03:00
|
|
|
#if HAL_VISUALODOM_ENABLED
|
|
|
|
AP_VisualOdom visual_odom;
|
|
|
|
#endif
|
|
|
|
|
2021-02-23 18:06:37 -04:00
|
|
|
#if HAL_WITH_ESC_TELEM
|
2020-02-11 02:15:39 -04:00
|
|
|
AP_ESC_Telem esc_telem;
|
2021-02-23 18:06:37 -04:00
|
|
|
#endif
|
2020-02-11 02:15:39 -04:00
|
|
|
|
2020-08-04 17:39:40 -03:00
|
|
|
#if HAL_MSP_ENABLED
|
|
|
|
AP_MSP msp;
|
|
|
|
#endif
|
|
|
|
|
2021-09-24 00:10:47 -03:00
|
|
|
#if HAL_GENERATOR_ENABLED
|
2020-10-22 14:17:26 -03:00
|
|
|
AP_Generator generator;
|
2019-11-06 20:38:53 -04:00
|
|
|
#endif
|
|
|
|
|
2020-12-27 22:06:14 -04:00
|
|
|
#if HAL_EXTERNAL_AHRS_ENABLED
|
|
|
|
AP_ExternalAHRS externalAHRS;
|
|
|
|
#endif
|
2021-01-29 15:55:49 -04:00
|
|
|
|
|
|
|
#if HAL_SMARTAUDIO_ENABLED
|
|
|
|
AP_SmartAudio smartaudio;
|
|
|
|
#endif
|
2021-02-01 12:26:35 -04:00
|
|
|
|
2021-10-21 03:37:35 -03:00
|
|
|
#if HAL_EFI_ENABLED
|
|
|
|
// EFI Engine Monitor
|
|
|
|
AP_EFI efi;
|
|
|
|
#endif
|
|
|
|
|
2022-01-03 17:17:01 -04:00
|
|
|
#if AP_AIRSPEED_ENABLED
|
|
|
|
AP_Airspeed airspeed;
|
|
|
|
#endif
|
|
|
|
|
2020-07-23 01:03:36 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
static const struct AP_Scheduler::Task scheduler_tasks[];
|
|
|
|
|
2020-12-05 14:46:16 -04:00
|
|
|
#if OSD_ENABLED
|
|
|
|
void publish_osd_info();
|
|
|
|
#endif
|
|
|
|
|
2021-08-16 23:51:35 -03:00
|
|
|
// update accel calibration
|
|
|
|
void accel_cal_update();
|
|
|
|
|
2021-02-02 19:48:14 -04:00
|
|
|
ModeReason control_mode_reason = ModeReason::UNKNOWN;
|
|
|
|
|
2021-10-06 01:51:07 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
SITL::SIM sitl;
|
|
|
|
#endif
|
|
|
|
|
2019-10-08 19:36:46 -03:00
|
|
|
private:
|
|
|
|
|
2020-02-25 07:21:59 -04:00
|
|
|
// delay() callback that processing MAVLink packets
|
2020-01-15 23:04:41 -04:00
|
|
|
static void scheduler_delay_callback();
|
|
|
|
|
2020-03-25 08:07:50 -03:00
|
|
|
// if there's been a watchdog reset, notify the world via a
|
|
|
|
// statustext:
|
|
|
|
void send_watchdog_reset_statustext();
|
|
|
|
|
2021-03-08 17:05:24 -04:00
|
|
|
// run notch update at either loop rate or 200Hz
|
|
|
|
void update_dynamic_notch_at_specified_rate();
|
|
|
|
|
2020-02-25 07:21:59 -04:00
|
|
|
bool likely_flying; // true if vehicle is probably flying
|
|
|
|
uint32_t _last_flying_ms; // time when likely_flying last went true
|
2021-03-08 17:05:24 -04:00
|
|
|
uint32_t _last_notch_update_ms; // last time update_dynamic_notch() was run
|
2020-02-25 07:21:59 -04:00
|
|
|
|
|
|
|
static AP_Vehicle *_singleton;
|
2020-11-30 23:52:29 -04:00
|
|
|
|
|
|
|
bool done_safety_init;
|
2021-08-28 13:18:07 -03:00
|
|
|
|
|
|
|
uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask
|
2019-10-08 19:36:46 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
AP_Vehicle *vehicle();
|
2013-09-12 22:43:59 -03:00
|
|
|
};
|
|
|
|
|
2018-12-27 02:31:34 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2015-05-13 05:32:34 -03:00
|
|
|
|
2019-12-18 18:35:32 -04:00
|
|
|
extern const AP_Param::Info vehicle_var_info[];
|
|
|
|
|
2015-05-24 20:48:51 -03:00
|
|
|
#include "AP_Vehicle_Type.h"
|