Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/Rover.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15main Rover class, containing all vehicle specific state16*/17#pragma once1819#include <cmath>20#include <stdarg.h>21#include <stdint.h>2223// Libraries24#include <AP_Common/AP_Common.h>25#include <AP_HAL/AP_HAL.h>26#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library27#include <AP_Camera/AP_Camera.h> // Camera triggering28#include <AP_Mount/AP_Mount.h> // Camera/Antenna mount29#include <AP_Param/AP_Param.h>30#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library31#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library32#include <AP_RPM/AP_RPM.h> // RPM input library33#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler34#include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build35#include <AP_WheelEncoder/AP_WheelEncoder.h>36#include <AP_WheelEncoder/AP_WheelRateControl.h>37#include <AP_Logger/AP_Logger.h>38#include <AP_OSD/AP_OSD.h>39#include <AR_Motors/AP_MotorsUGV.h>40#include <AP_Mission/AP_Mission.h>41#include <AP_Mission/AP_Mission_ChangeDetector.h>42#include <AR_WPNav/AR_WPNav_OA.h>43#include <AP_OpticalFlow/AP_OpticalFlow.h>44#include <AC_PrecLand/AC_PrecLand_config.h>45#include <AP_Follow/AP_Follow_config.h>46#include <AP_ExternalControl/AP_ExternalControl_config.h>47#if AP_EXTERNAL_CONTROL_ENABLED48#include "AP_ExternalControl_Rover.h"49#endif5051// Configuration52#include "defines.h"53#include "config.h"5455#if AP_SCRIPTING_ENABLED56#include <AP_Scripting/AP_Scripting.h>57#endif5859// Local modules60#include "AP_Arming.h"61#include "sailboat.h"62#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED63#include "afs_rover.h"64#endif65#include "Parameters.h"66#include "GCS_MAVLink_Rover.h"67#include "GCS_Rover.h"68#include "AP_Rally.h"69#if AC_PRECLAND_ENABLED70#include <AC_PrecLand/AC_PrecLand.h>71#endif72#include "RC_Channel_Rover.h" // RC Channel Library7374#include "mode.h"7576class Rover : public AP_Vehicle {77public:78friend class GCS_MAVLINK_Rover;79friend class Parameters;80friend class ParametersG2;81friend class AP_Rally_Rover;82friend class AP_Arming_Rover;83#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED84friend class AP_AdvancedFailsafe_Rover;85#endif86#if AP_EXTERNAL_CONTROL_ENABLED87friend class AP_ExternalControl_Rover;88#endif89friend class GCS_Rover;90friend class Mode;91friend class ModeAcro;92friend class ModeAuto;93friend class ModeCircle;94friend class ModeGuided;95friend class ModeHold;96friend class ModeLoiter;97friend class ModeSteering;98friend class ModeManual;99friend class ModeRTL;100friend class ModeSmartRTL;101#if MODE_FOLLOW_ENABLED102friend class ModeFollow;103#endif104friend class ModeSimple;105#if MODE_DOCK_ENABLED106friend class ModeDock;107#endif108109friend class RC_Channel_Rover;110friend class RC_Channels_Rover;111112friend class Sailboat;113114Rover(void);115116private:117118// must be the first AP_Param variable declared to ensure its119// constructor runs before the constructors of the other AP_Param120// variables121AP_Param param_loader;122123// all settable parameters124Parameters g;125ParametersG2 g2;126127// mapping between input channels128RCMapper rcmap;129130// primary control channels131RC_Channel *channel_steer;132RC_Channel *channel_throttle;133RC_Channel *channel_lateral;134RC_Channel *channel_roll;135RC_Channel *channel_pitch;136RC_Channel *channel_walking_height;137138// flight modes convenience array139AP_Int8 *modes;140const uint8_t num_modes = 6;141142#if AP_RPM_ENABLED143// AP_RPM Module144AP_RPM rpm_sensor;145#endif146147// Arming/Disarming management class148AP_Arming_Rover arming;149150// external control implementation151#if AP_EXTERNAL_CONTROL_ENABLED152AP_ExternalControl_Rover external_control;153#endif154155#if AP_OPTICALFLOW_ENABLED156AP_OpticalFlow optflow;157#endif158159#if OSD_ENABLED || OSD_PARAM_ENABLED160AP_OSD osd;161#endif162#if AC_PRECLAND_ENABLED163AC_PrecLand precland;164#endif165// GCS handling166GCS_Rover _gcs; // avoid using this; use gcs()167GCS_Rover &gcs() { return _gcs; }168169// RC Channels:170RC_Channels_Rover &rc() { return g2.rc_channels; }171172// The rover's current location173Location current_loc;174175// Camera176#if AP_CAMERA_ENABLED177AP_Camera camera{MASK_LOG_CAMERA};178#endif179180// Camera/Antenna mount tracking and stabilisation stuff181#if HAL_MOUNT_ENABLED182AP_Mount camera_mount;183#endif184185// true if initialisation has completed186bool initialised;187188// This is the state of the flight control system189// There are multiple states defined such as MANUAL, AUTO, ...190Mode *control_mode;191192// Used to maintain the state of the previous control switch position193// This is set to -1 when we need to re-read the switch194uint8_t oldSwitchPosition;195196// structure for holding failsafe state197struct {198uint8_t bits; // bit flags of failsafes that have started (but not necessarily triggered an action)199uint32_t start_time; // start time of the earliest failsafe200uint8_t triggered; // bit flags of failsafes that have triggered an action201uint32_t last_valid_rc_ms; // system time of most recent RC input from pilot202bool ekf;203} failsafe;204205// true if we have a position estimate from AHRS206bool have_position;207208#if AP_RANGEFINDER_ENABLED209// range finder last update for each instance (used for DPTH logging)210uint32_t rangefinder_last_reading_ms[RANGEFINDER_MAX_INSTANCES];211#endif212213// Ground speed214// The amount current ground speed is below min ground speed. meters per second215float ground_speed;216217// Battery Sensors218AP_BattMonitor battery{MASK_LOG_CURRENT,219FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t),220_failsafe_priorities};221222// flyforward timer223uint32_t flyforward_start_ms;224225static const AP_Scheduler::Task scheduler_tasks[];226227static const AP_Param::Info var_info[];228#if HAL_LOGGING_ENABLED229static const LogStructure log_structure[];230#endif231232// time that rudder/steering arming has been running233uint32_t rudder_arm_timer;234235// latest wheel encoder values236float wheel_encoder_last_distance_m[WHEELENCODER_MAX_INSTANCES]; // total distance recorded by wheel encoder (for reporting to GCS)237bool wheel_encoder_initialised; // true once arrays below have been initialised to sensors initial values238float wheel_encoder_last_angle_rad[WHEELENCODER_MAX_INSTANCES]; // distance in radians at time of last update to EKF239uint32_t wheel_encoder_last_reading_ms[WHEELENCODER_MAX_INSTANCES]; // system time of last ping from each encoder240uint8_t wheel_encoder_last_index_sent; // index of the last wheel encoder sent to the EKF241242// True when we are doing motor test243bool motor_test;244245ModeInitializing mode_initializing;246ModeHold mode_hold;247ModeManual mode_manual;248ModeAcro mode_acro;249ModeGuided mode_guided;250ModeAuto mode_auto;251ModeLoiter mode_loiter;252ModeSteering mode_steering;253ModeRTL mode_rtl;254ModeSmartRTL mode_smartrtl;255#if MODE_FOLLOW_ENABLED256ModeFollow mode_follow;257#endif258ModeSimple mode_simple;259#if MODE_DOCK_ENABLED260ModeDock mode_dock;261#endif262263// cruise throttle and speed learning264typedef struct {265LowPassFilterFloat speed_filt{2.0f};266LowPassFilterFloat throttle_filt{2.0f};267uint32_t learn_start_ms;268uint32_t log_count;269} cruise_learn_t;270cruise_learn_t cruise_learn;271272// Rover.cpp273#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED274bool set_target_location(const Location& target_loc) override;275#endif276277#if AP_SCRIPTING_ENABLED278bool set_target_velocity_NED(const Vector3f& vel_ned) override;279bool set_steering_and_throttle(float steering, float throttle) override;280bool get_steering_and_throttle(float& steering, float& throttle) override;281// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting282bool set_desired_turn_rate_and_speed(float turn_rate, float speed) override;283bool set_desired_speed(float speed) override;284bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;285bool nav_scripting_enable(uint8_t mode) override;286bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) override;287void nav_script_time_done(uint16_t id) override;288#endif // AP_SCRIPTING_ENABLED289void ahrs_update();290void gcs_failsafe_check(void);291void update_logging1(void);292void update_logging2(void);293void one_second_loop(void);294void update_current_mode(void);295296// balance_bot.cpp297void balancebot_pitch_control(float &throttle);298bool is_balancebot() const;299300// commands.cpp301bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;302bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;303void update_home();304305// crash_check.cpp306void crash_check();307308// cruise_learn.cpp309void cruise_learn_start();310void cruise_learn_update();311void cruise_learn_complete();312void log_write_cruise_learn() const;313314// ekf_check.cpp315void ekf_check();316bool ekf_over_threshold();317bool ekf_position_ok();318void failsafe_ekf_event();319void failsafe_ekf_off_event(void);320321// failsafe.cpp322void failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool on);323void handle_battery_failsafe(const char* type_str, const int8_t action);324#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED325void afs_fs_check(void);326#endif327328// fence.cpp329void fence_check();330331// GCS_Mavlink.cpp332void send_wheel_encoder_distance(mavlink_channel_t chan);333334#if HAL_LOGGING_ENABLED335// methods for AP_Vehicle:336const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }337const struct LogStructure *get_log_structures() const override {338return log_structure;339}340uint8_t get_num_log_structures() const override;341342// Log.cpp343void Log_Write_Attitude();344void Log_Write_Depth();345void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);346void Log_Write_Nav_Tuning();347void Log_Write_Sail();348void Log_Write_Steering();349void Log_Write_Throttle();350void Log_Write_RC(void);351void Log_Write_Vehicle_Startup_Messages();352void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page);353#endif354355// mode.cpp356Mode *mode_from_mode_num(enum Mode::Number num);357358// Parameters.cpp359void load_parameters(void) override;360361// precision_landing.cpp362void init_precland();363void update_precland();364365// radio.cpp366void set_control_channels(void) override;367void init_rc_in();368void rudder_arm_disarm_check();369void read_radio();370void radio_failsafe_check(uint16_t pwm);371372// sensors.cpp373void update_compass(void);374void compass_save(void);375void update_wheel_encoder();376#if AP_RANGEFINDER_ENABLED377void read_rangefinders(void);378#endif379380// Steering.cpp381void set_servos(void);382383// Rover.cpp384void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,385uint8_t &task_count,386uint32_t &log_bit) override;387388// system.cpp389void init_ardupilot() override;390void startup_ground(void);391void update_ahrs_flyforward();392bool gcs_mode_enabled(const Mode::Number mode_num) const;393bool set_mode(Mode &new_mode, ModeReason reason);394bool set_mode(const uint8_t new_mode, ModeReason reason) override;395bool set_mode(Mode::Number new_mode, ModeReason reason);396uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }397bool current_mode_requires_mission() const override {398return control_mode == &mode_auto;399}400401void startup_INS(void);402void notify_mode(const Mode *new_mode);403uint8_t check_digital_pin(uint8_t pin);404bool should_log(uint32_t mask);405bool is_boat() const;406407// vehicle specific waypoint info helpers408bool get_wp_distance_m(float &distance) const override;409bool get_wp_bearing_deg(float &bearing) const override;410bool get_wp_crosstrack_error_m(float &xtrack_error) const override;411412enum class FailsafeAction: int8_t {413None = 0,414RTL = 1,415Hold = 2,416SmartRTL = 3,417SmartRTL_Hold = 4,418Terminate = 5419};420421enum class Failsafe_Options : uint32_t {422Failsafe_Option_Active_In_Hold = (1<<0)423};424425static constexpr int8_t _failsafe_priorities[] = {426(int8_t)FailsafeAction::Terminate,427(int8_t)FailsafeAction::Hold,428(int8_t)FailsafeAction::RTL,429(int8_t)FailsafeAction::SmartRTL_Hold,430(int8_t)FailsafeAction::SmartRTL,431(int8_t)FailsafeAction::None,432-1 // the priority list must end with a sentinel of -1433};434static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,435"_failsafe_priorities is missing the sentinel");436437438public:439void failsafe_check();440// Motor test441void motor_test_output();442bool mavlink_motor_test_check(const GCS_MAVLINK &gcs_chan, bool check_rc, AP_MotorsUGV::motor_test_order motor_instance, uint8_t throttle_type, int16_t throttle_value);443MAV_RESULT mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_MotorsUGV::motor_test_order motor_instance, uint8_t throttle_type, int16_t throttle_value, float timeout_sec);444void motor_test_stop();445446// frame type447uint8_t get_frame_type() const { return g2.frame_type.get(); }448AP_WheelRateControl& get_wheel_rate_control() { return g2.wheel_rate_control; }449450// Simple mode451float simple_sin_yaw;452};453454extern Rover rover;455456using AP_HAL::millis;457using AP_HAL::micros;458459460