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/ArduSub/defines.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL_Boards.h>34#define BOTTOM_DETECTOR_TRIGGER_SEC 1.05#define SURFACE_DETECTOR_TRIGGER_SEC 1.067enum AutoSurfaceState {8AUTO_SURFACE_STATE_GO_TO_LOCATION,9AUTO_SURFACE_STATE_ASCEND10};1112// Autopilot Yaw Mode enumeration13enum autopilot_yaw_mode {14AUTO_YAW_HOLD = 0, // pilot controls the heading15AUTO_YAW_LOOK_AT_NEXT_WP = 1, // point towards next waypoint (no pilot input accepted)16AUTO_YAW_ROI = 2, // point towards a location held in roi_WP (no pilot input accepted)17AUTO_YAW_LOOK_AT_HEADING = 3, // point towards a particular angle (not pilot input accepted)18AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the vehicle is moving19AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed20AUTO_YAW_CORRECT_XTRACK = 6, // steer the sub in order to correct for crosstrack error during line following21AUTO_YAW_RATE = 7 // steer the sub with the desired yaw rate22};2324// Acro Trainer types25#define ACRO_TRAINER_DISABLED 026#define ACRO_TRAINER_LEVELING 127#define ACRO_TRAINER_LIMITED 22829// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter30#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)31#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl32#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last33#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters)34#define WP_YAW_BEHAVIOR_CORRECT_XTRACK 4 // point towards intermediate position target during line following35363738// Logging parameters - only 32 messages are available to the vehicle here.39enum LoggingParameters {40LOG_CONTROL_TUNING_MSG,41LOG_DATA_INT16_MSG,42LOG_DATA_UINT16_MSG,43LOG_DATA_INT32_MSG,44LOG_DATA_UINT32_MSG,45LOG_DATA_FLOAT_MSG,46LOG_GUIDEDTARGET_MSG47};4849#define MASK_LOG_ATTITUDE_FAST (1<<0)50#define MASK_LOG_ATTITUDE_MED (1<<1)51#define MASK_LOG_GPS (1<<2)52#define MASK_LOG_PM (1<<3)53#define MASK_LOG_CTUN (1<<4)54#define MASK_LOG_NTUN (1<<5)55#define MASK_LOG_RCIN (1<<6)56#define MASK_LOG_IMU (1<<7)57#define MASK_LOG_CMD (1<<8)58#define MASK_LOG_CURRENT (1<<9)59#define MASK_LOG_RCOUT (1<<10)60#define MASK_LOG_OPTFLOW (1<<11)61#define MASK_LOG_PID (1<<12)62#define MASK_LOG_COMPASS (1<<13)63#define MASK_LOG_CAMERA (1<<15)64#define MASK_LOG_MOTBATT (1UL<<17)65#define MASK_LOG_IMU_FAST (1UL<<18)66#define MASK_LOG_IMU_RAW (1UL<<19)67#define MASK_LOG_ANY 0xFFFF6869// GCS failsafe70#ifndef FS_GCS71# define FS_GCS 072#endif73#ifndef FS_GCS_TIMEOUT_S74# define FS_GCS_TIMEOUT_S 5.0 // gcs failsafe triggers after this number of seconds with no GCS heartbeat75#endif7677// missing terrain data failsafe78#ifndef FS_TERRAIN_TIMEOUT_MS79#define FS_TERRAIN_TIMEOUT_MS 1000 // 1 second of unhealthy rangefinder and/or missing terrain data will trigger failsafe80#endif8182//////////////////////////////////////////////////////////////////////////////83// EKF Failsafe84// EKF failsafe definitions (FS_EKF_ENABLE parameter)85#define FS_EKF_ACTION_DISABLED 0 // Disabled86#define FS_EKF_ACTION_WARN_ONLY 1 // Send warning to gcs87#define FS_EKF_ACTION_DISARM 2 // Disarm888990#ifndef FS_EKF_ACTION_DEFAULT91# define FS_EKF_ACTION_DEFAULT FS_EKF_ACTION_DISABLED // EKF failsafe92#endif9394#ifndef FS_EKF_THRESHOLD_DEFAULT95# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered96#endif9798// GCS failsafe definitions (FS_GCS_ENABLE parameter)99#define FS_GCS_DISABLED 0 // Disabled100#define FS_GCS_WARN_ONLY 1 // Only send warning to gcs (only useful with multiple gcs links)101#define FS_GCS_DISARM 2 // Disarm102#define FS_GCS_HOLD 3 // Switch depth hold mode or poshold mode if available103#define FS_GCS_SURFACE 4 // Switch to surface mode104105// Leak failsafe definitions (FS_LEAK_ENABLE parameter)106#define FS_LEAK_DISABLED 0 // Disabled107#define FS_LEAK_WARN_ONLY 1 // Only send warning to gcs108#define FS_LEAK_SURFACE 2 // Switch to surface mode109110// Internal pressure failsafe threshold (FS_PRESS_MAX parameter)111#define FS_PRESS_MAX_DEFAULT 105000 // Maximum internal pressure in pascal before failsafe is triggered112// Internal pressure failsafe definitions (FS_PRESS_ENABLE parameter)113#define FS_PRESS_DISABLED 0114#define FS_PRESS_WARN_ONLY 1115116// Internal temperature failsafe threshold (FS_TEMP_MAX parameter)117#define FS_TEMP_MAX_DEFAULT 62 // Maximum internal pressure in degrees C before failsafe is triggered118// Internal temperature failsafe definitions (FS_TEMP_ENABLE parameter)119#define FS_TEMP_DISABLED 0120#define FS_TEMP_WARN_ONLY 1121122// Crash failsafe options123#define FS_CRASH_DISABLED 0124#define FS_CRASH_WARN_ONLY 1125#define FS_CRASH_DISARM 2126127// Terrain failsafe actions for AUTO mode128#define FS_TERRAIN_DISARM 0129#define FS_TERRAIN_HOLD 1130#define FS_TERRAIN_SURFACE 2131132// Pilot input failsafe actions133#define FS_PILOT_INPUT_DISABLED 0134#define FS_PILOT_INPUT_WARN_ONLY 1135#define FS_PILOT_INPUT_DISARM 2136137// Amount of time to attempt recovery of valid rangefinder data before138// initiating terrain failsafe action139#define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000140141// for mavlink SET_POSITION_TARGET messages142#define MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE (1<<2)143#define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2))144#define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5))145#define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8))146#define MAVLINK_SET_POS_TYPE_MASK_FORCE (1<<9)147#define MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE (1<<10)148#define MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE (1<<11)149150151152