Sub.h 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. /*
  15. This is the main Sub class
  16. */
  17. ////////////////////////////////////////////////////////////////////////////////
  18. // Header includes
  19. ////////////////////////////////////////////////////////////////////////////////
  20. #include <cmath>
  21. #include <stdio.h>
  22. #include <stdarg.h>
  23. #include <AP_HAL/AP_HAL.h>
  24. // Common dependencies
  25. #include <AP_Common/AP_Common.h>
  26. #include <AP_Common/Location.h>
  27. #include <AP_Param/AP_Param.h>
  28. #include <StorageManager/StorageManager.h>
  29. #include <GCS_MAVLink/GCS.h>
  30. #include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
  31. #include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
  32. #include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
  33. // Application dependencies
  34. #include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
  35. #include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
  36. #include <AP_Logger/AP_Logger.h> // ArduPilot Mega Flash Memory Library
  37. #include <AP_Baro/AP_Baro.h>
  38. #include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
  39. #include <AP_InertialSensor/AP_InertialSensor.h> // ArduPilot Mega Inertial Sensor (accel & gyro) Library
  40. #include <AP_AHRS/AP_AHRS.h>
  41. #include <AP_NavEKF2/AP_NavEKF2.h>
  42. #include <AP_NavEKF3/AP_NavEKF3.h>
  43. #include <AP_Mission/AP_Mission.h> // Mission command library
  44. #include <AC_PID/AC_P.h> // P library
  45. #include <AC_PID/AC_PID.h> // PID library
  46. #include <AC_PID/AC_PI_2D.h> // PI library (2-axis)
  47. #include <AC_PID/AC_PID_2D.h> // PID library (2-axis)
  48. #include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library
  49. #include <AC_AttitudeControl/AC_PosControl_Sub.h> // Position control library
  50. #include <AP_Motors/AP_Motors.h> // AP Motors library
  51. #include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
  52. #include <Filter/Filter.h> // Filter library
  53. #include <AP_Relay/AP_Relay.h> // APM relay
  54. #include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
  55. #include <AP_Mount/AP_Mount.h> // Camera/Antenna mount
  56. #include <AP_Vehicle/AP_Vehicle.h> // needed for AHRS build
  57. #include <AP_InertialNav/AP_InertialNav.h> // ArduPilot Mega inertial navigation library
  58. #include <AC_WPNav/AC_WPNav.h> // Waypoint navigation library
  59. #include <AC_WPNav/AC_Loiter.h>
  60. #include <AC_WPNav/AC_Circle.h> // circle navigation library
  61. #include <AC_Fence/AC_Fence.h> // Fence library
  62. #include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
  63. #include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
  64. #include <AP_Notify/AP_Notify.h> // Notify library
  65. #include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
  66. #include <AP_BoardConfig/AP_BoardConfig.h> // board configuration library
  67. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  68. #include <AP_Terrain/AP_Terrain.h>
  69. #include <AP_JSButton/AP_JSButton.h> // Joystick/gamepad button function assignment
  70. #include <AP_LeakDetector/AP_LeakDetector.h> // Leak detector
  71. #include <AP_TemperatureSensor/TSYS01.h>
  72. #include <AP_Common/AP_FWVersion.h>
  73. // Local modules
  74. #include "defines.h"
  75. #include "config.h"
  76. #include "GCS_Mavlink.h"
  77. #include "RC_Channel.h" // RC Channel Library
  78. #include "Parameters.h"
  79. #include "AP_Arming_Sub.h"
  80. #include "GCS_Sub.h"
  81. //------self define start-------------------
  82. #include "Gearmotorpid.h"
  83. #define OUSHENCAN_MAX_NUM_ESCS 6
  84. #ifndef USERHOOK_50HZLOOP
  85. #define USERHOOK_50HZLOOP 1
  86. #endif
  87. #define startval 0
  88. #define Speedmax_hand 62
  89. #define Speedmax_hand_f 62.0
  90. #define speedmin 31
  91. #define maxerror 41//31
  92. #define maxerror_f 41.0//31.0
  93. #define Horizontal 0
  94. #define Vertical 1
  95. #define section0 0
  96. #define section90 1
  97. #define section_90 2
  98. #define action_Hor 0
  99. #define action_Ver_postive 1
  100. #define action_Ver_negtive 2
  101. #define Orign 0
  102. #define foward 1
  103. #define backward 2
  104. #define Speedmax 60
  105. //压力等级 包含下压和上浮总共10级 第五级为1500 即中值
  106. enum PressNetLevel {
  107. first = 0,
  108. second = 1,
  109. third = 2,
  110. forth = 3,
  111. fifth = 4,
  112. no =5,
  113. sixth = 6,
  114. seventh = 7,
  115. eighth = 8,
  116. ninth = 9,
  117. tenth = 10
  118. };
  119. #define SaberDatapacketID 0x8106
  120. #define RespAllStatusID 0x8602
  121. #define SystemResetAckID 0x8401
  122. #define Saber_selftest_Failed 0x08 //自检失败
  123. #define Saber_WakeUpHost 0x0101 //WakeUp模式
  124. #define Saber_MesureMode 0x02 //测量模式
  125. //usigned char to float将char类型转换成float类型
  126. typedef union{
  127. unsigned char u[4];
  128. float f;
  129. }uTof;
  130. //------self define end-------------------
  131. // libraries which are dependent on #defines in defines.h and/or config.h
  132. #if OPTFLOW == ENABLED
  133. #include <AP_OpticalFlow/AP_OpticalFlow.h> // Optical Flow library
  134. #endif
  135. #if RCMAP_ENABLED == ENABLED
  136. #include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
  137. #endif
  138. #if RPM_ENABLED == ENABLED
  139. #include <AP_RPM/AP_RPM.h>
  140. #endif
  141. #if GRIPPER_ENABLED == ENABLED
  142. #include <AP_Gripper/AP_Gripper.h> // gripper stuff
  143. #endif
  144. #if PROXIMITY_ENABLED == ENABLED
  145. #include <AP_Proximity/AP_Proximity.h>
  146. #endif
  147. #if AVOIDANCE_ENABLED == ENABLED
  148. #include <AC_Avoidance/AC_Avoid.h> // Stop at fence library
  149. #endif
  150. #if AC_RALLY == ENABLED
  151. #include <AP_Rally/AP_Rally.h> // Rally point library
  152. #endif
  153. #if CAMERA == ENABLED
  154. #include <AP_Camera/AP_Camera.h> // Photo or video camera
  155. #endif
  156. #ifdef ENABLE_SCRIPTING
  157. #include <AP_Scripting/AP_Scripting.h>
  158. #endif
  159. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  160. #include <SITL/SITL.h>
  161. #endif
  162. class Sub : public AP_HAL::HAL::Callbacks {
  163. public:
  164. friend class GCS_MAVLINK_Sub;
  165. friend class GCS_Sub;
  166. friend class Parameters;
  167. friend class ParametersG2;
  168. friend class AP_Arming_Sub;
  169. friend class RC_Channels_Sub;
  170. Sub(void);
  171. // HAL::Callbacks implementation.
  172. void setup() override;
  173. void loop() override;
  174. private:
  175. static const AP_FWVersion fwver;
  176. // key aircraft parameters passed to multiple libraries
  177. AP_Vehicle::MultiCopter aparm;
  178. // Global parameters are all contained within the 'g' class.
  179. Parameters g;
  180. ParametersG2 g2;
  181. // main loop scheduler
  182. AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Sub::fast_loop, void)};
  183. // AP_Notify instance
  184. AP_Notify notify;
  185. // primary input control channels
  186. RC_Channel *channel_roll;
  187. RC_Channel *channel_pitch;
  188. RC_Channel *channel_throttle;
  189. RC_Channel *channel_yaw;
  190. RC_Channel *channel_forward;
  191. RC_Channel *channel_lateral;
  192. AP_Logger logger;
  193. AP_GPS gps;
  194. AP_LeakDetector leak_detector;
  195. TSYS01 celsius;
  196. Compass compass;
  197. AP_InertialSensor ins;
  198. RangeFinder rangefinder;
  199. struct {
  200. bool enabled:1;
  201. bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
  202. int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder
  203. uint32_t last_healthy_ms;
  204. LowPassFilterFloat alt_cm_filt; // altitude filter
  205. } rangefinder_state = { false, false, 0, 0 };
  206. #if RPM_ENABLED == ENABLED
  207. AP_RPM rpm_sensor;
  208. #endif
  209. // Inertial Navigation EKF
  210. NavEKF2 EKF2{&ahrs, rangefinder};
  211. NavEKF3 EKF3{&ahrs, rangefinder};
  212. AP_AHRS_NavEKF ahrs{EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
  213. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  214. SITL::SITL sitl;
  215. #endif
  216. // Mission library
  217. AP_Mission mission{
  218. FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
  219. FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),
  220. FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)};
  221. // Optical flow sensor
  222. #if OPTFLOW == ENABLED
  223. OpticalFlow optflow;
  224. #endif
  225. // system time in milliseconds of last recorded yaw reset from ekf
  226. uint32_t ekfYawReset_ms = 0;
  227. AP_SerialManager serial_manager;
  228. // GCS selection
  229. GCS_Sub _gcs; // avoid using this; use gcs()
  230. GCS_Sub &gcs() { return _gcs; }
  231. // User variables
  232. #ifdef USERHOOK_VARIABLES
  233. # include USERHOOK_VARIABLES
  234. #endif
  235. // Documentation of Globals:
  236. union {
  237. struct {
  238. uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
  239. uint8_t logging_started : 1; // true if logging has started
  240. uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
  241. uint8_t motor_test : 1; // true if we are currently performing the motors test
  242. uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
  243. uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
  244. uint8_t at_bottom : 1; // true if we are at the bottom
  245. uint8_t at_surface : 1; // true if we are at the surface
  246. uint8_t depth_sensor_present: 1; // true if there is a depth sensor detected at boot
  247. uint8_t compass_init_location:1; // true when the compass's initial location has been set
  248. };
  249. uint32_t value;
  250. } ap;
  251. // This is the state of the flight control system
  252. // There are multiple states defined such as STABILIZE, ACRO,
  253. #if RCMAP_ENABLED == ENABLED
  254. RCMapper rcmap;
  255. #endif
  256. // board specific config
  257. AP_BoardConfig BoardConfig;
  258. #if HAL_WITH_UAVCAN
  259. // board specific config for CAN bus
  260. AP_BoardConfig_CAN BoardConfig_CAN;
  261. #endif
  262. // Failsafe
  263. struct {
  264. uint32_t last_leak_warn_ms; // last time a leak warning was sent to gcs
  265. uint32_t last_gcs_warn_ms;
  266. uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
  267. uint32_t last_pilot_input_ms; // last time we received pilot input in the form of MANUAL_CONTROL or RC_CHANNELS_OVERRIDE messages
  268. uint32_t terrain_first_failure_ms; // the first time terrain data access failed - used to calculate the duration of the failure
  269. uint32_t terrain_last_failure_ms; // the most recent time terrain data access failed
  270. uint32_t last_crash_warn_ms; // last time a crash warning was sent to gcs
  271. uint32_t last_ekf_warn_ms; // last time an ekf warning was sent to gcs
  272. uint8_t pilot_input : 1; // true if pilot input failsafe is active, handles things like joystick being disconnected during operation
  273. uint8_t gcs : 1; // A status flag for the ground station failsafe
  274. uint8_t ekf : 1; // true if ekf failsafe has occurred
  275. uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred
  276. uint8_t leak : 1; // true if leak recently detected
  277. uint8_t internal_pressure : 1; // true if internal pressure is over threshold
  278. uint8_t internal_temperature : 1; // true if temperature is over threshold
  279. uint8_t crash : 1; // true if we are crashed
  280. uint8_t sensor_health : 1; // true if at least one sensor has triggered a failsafe (currently only used for depth in depth enabled modes)
  281. } failsafe;
  282. bool any_failsafe_triggered() const {
  283. return (failsafe.pilot_input || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain);
  284. }
  285. // sensor health for logging
  286. struct {
  287. uint8_t baro : 1; // true if any single baro is healthy
  288. uint8_t depth : 1; // true if depth sensor is healthy
  289. uint8_t compass : 1; // true if compass is healthy
  290. } sensor_health;
  291. // Baro sensor instance index of the external water pressure sensor
  292. uint8_t depth_sensor_idx;
  293. // GPS variables
  294. // Sometimes we need to remove the scaling for distance calcs
  295. float scaleLongDown;
  296. // Auto
  297. AutoMode auto_mode; // controls which auto controller is run
  298. // Guided
  299. GuidedMode guided_mode; // controls which controller is run (pos or vel)
  300. // Circle
  301. bool circle_pilot_yaw_override; // true if pilot is overriding yaw
  302. // Stores initial bearing when armed
  303. int32_t initial_armed_bearing;
  304. // Throttle variables
  305. int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only
  306. // Loiter control
  307. uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds)
  308. uint32_t loiter_time; // How long have we been loitering - The start time in millis
  309. // Delay the next navigation command
  310. uint32_t nav_delay_time_max_ms; // used for delaying the navigation commands
  311. uint32_t nav_delay_time_start_ms;
  312. // Battery Sensors
  313. AP_BattMonitor battery{MASK_LOG_CURRENT,
  314. FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),
  315. _failsafe_priorities};
  316. // Altitude
  317. // The cm/s we are moving up or down based on filtered data - Positive = UP
  318. int16_t climb_rate;
  319. float target_rangefinder_alt; // desired altitude in cm above the ground
  320. bool holding_depth;
  321. // Turn counter
  322. int32_t quarter_turn_count;
  323. uint8_t last_turn_state;
  324. // Input gain
  325. float gain;
  326. // Flag indicating if we are currently using input hold
  327. bool input_hold_engaged;
  328. // 3D Location vectors
  329. // Current location of the Sub (altitude is relative to home)
  330. Location current_loc;
  331. // Navigation Yaw control
  332. // auto flight mode's yaw mode
  333. uint8_t auto_yaw_mode;
  334. // Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI
  335. Vector3f roi_WP;
  336. // bearing from current location to the yaw_look_at_WP
  337. float yaw_look_at_WP_bearing;
  338. float yaw_xtrack_correct_heading;
  339. // yaw used for YAW_LOOK_AT_HEADING yaw_mode
  340. int32_t yaw_look_at_heading;
  341. // Deg/s we should turn
  342. int16_t yaw_look_at_heading_slew;
  343. // heading when in yaw_look_ahead_bearing
  344. float yaw_look_ahead_bearing;
  345. // Delay Mission Scripting Command
  346. int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
  347. uint32_t condition_start;
  348. // IMU variables
  349. // Integration time (in seconds) for the gyros (DCM algorithm)
  350. // Updated with the fast loop
  351. float G_Dt;
  352. // Inertial Navigation
  353. AP_InertialNav_NavEKF inertial_nav;
  354. AP_AHRS_View ahrs_view;
  355. // Attitude, Position and Waypoint navigation objects
  356. // To-Do: move inertial nav up or other navigation variables down here
  357. AC_AttitudeControl_Sub attitude_control;
  358. AC_PosControl_Sub pos_control;
  359. AC_WPNav wp_nav;
  360. AC_Loiter loiter_nav;
  361. AC_Circle circle_nav;
  362. // Reference to the relay object
  363. AP_Relay relay;
  364. // handle repeated servo and relay events
  365. AP_ServoRelayEvents ServoRelayEvents;
  366. // Camera
  367. #if CAMERA == ENABLED
  368. AP_Camera camera{MASK_LOG_CAMERA, current_loc};
  369. #endif
  370. // Camera/Antenna mount tracking and stabilisation stuff
  371. #if MOUNT == ENABLED
  372. // current_loc uses the baro/gps soloution for altitude rather than gps only.
  373. AP_Mount camera_mount{current_loc};
  374. #endif
  375. // AC_Fence library to reduce fly-aways
  376. #if AC_FENCE == ENABLED
  377. AC_Fence fence;
  378. #endif
  379. #if AVOIDANCE_ENABLED == ENABLED
  380. AC_Avoid avoid;
  381. #endif
  382. // Rally library
  383. #if AC_RALLY == ENABLED
  384. AP_Rally rally;
  385. #endif
  386. // terrain handling
  387. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  388. AP_Terrain terrain{mission};
  389. #endif
  390. // used to allow attitude and depth control without a position system
  391. struct attitude_no_gps_struct {
  392. uint32_t last_message_ms;
  393. mavlink_set_attitude_target_t packet;
  394. };
  395. attitude_no_gps_struct set_attitude_target_no_gps {0};
  396. // Top-level logic
  397. // setup the var_info table
  398. AP_Param param_loader;
  399. uint32_t last_pilot_heading;
  400. uint32_t last_input_ms;
  401. uint32_t last_input_ms_stable;
  402. int32_t last_roll_s;
  403. int32_t last_pitch_s;
  404. int32_t last_yaw_s;
  405. int32_t last_roll;
  406. int32_t last_pitch;
  407. int32_t last_yaw;
  408. uint32_t last_pilot_yaw_input_ms;
  409. uint32_t fs_terrain_recover_start_ms;
  410. static const AP_Scheduler::Task scheduler_tasks[];
  411. static const AP_Param::Info var_info[];
  412. static const struct LogStructure log_structure[];
  413. void fast_loop();
  414. void fifty_hz_loop();
  415. void update_batt_compass(void);
  416. void ten_hz_logging_loop();
  417. void twentyfive_hz_logging();
  418. void three_hz_loop();
  419. void one_hz_loop();
  420. void update_GPS(void);
  421. void update_turn_counter();
  422. void read_AHRS(void);
  423. void update_altitude();
  424. float get_smoothing_gain();
  425. void get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max);
  426. float get_pilot_desired_yaw_rate(int16_t stick_angle);
  427. void check_ekf_yaw_reset();
  428. float get_roi_yaw();
  429. float get_look_ahead_yaw();
  430. float get_pilot_desired_climb_rate(float throttle_control);
  431. float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
  432. void update_poscon_alt_max();
  433. void rotate_body_frame_to_NE(float &x, float &y);
  434. void send_heartbeat(mavlink_channel_t chan);
  435. #if RPM_ENABLED == ENABLED
  436. void rpm_update();
  437. #endif
  438. void Log_Write_Control_Tuning();
  439. void Log_Write_Performance();
  440. void Log_Write_Attitude();
  441. void Log_Write_MotBatt();
  442. void Log_Write_Event(Log_Event id);
  443. void Log_Write_Data(uint8_t id, int32_t value);
  444. void Log_Write_Data(uint8_t id, uint32_t value);
  445. void Log_Write_Data(uint8_t id, int16_t value);
  446. void Log_Write_Data(uint8_t id, uint16_t value);
  447. void Log_Write_Data(uint8_t id, float value);
  448. void Log_Sensor_Health();
  449. void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
  450. void Log_Write_Vehicle_Startup_Messages();
  451. void load_parameters(void);
  452. void userhook_init();
  453. void userhook_FastLoop();
  454. void userhook_50Hz();
  455. void userhook_MediumLoop();
  456. void userhook_SlowLoop();
  457. void userhook_SuperSlowLoop();
  458. void update_home_from_EKF();
  459. void set_home_to_current_location_inflight();
  460. bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
  461. bool set_home(const Location& loc, bool lock) WARN_IF_UNUSED;
  462. bool far_from_EKF_origin(const Location& loc);
  463. void exit_mission();
  464. bool verify_loiter_unlimited();
  465. bool verify_loiter_time();
  466. bool verify_wait_delay();
  467. bool verify_within_distance();
  468. bool verify_yaw();
  469. bool acro_init(void);
  470. void acro_run();
  471. 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);
  472. bool althold_init(void);
  473. void althold_run();
  474. // Handles attitude control for stabilize and althold modes
  475. void handle_attitude();
  476. bool auto_init(void);
  477. void auto_run();
  478. void auto_wp_start(const Vector3f& destination);
  479. void auto_wp_start(const Location& dest_loc);
  480. void auto_wp_run();
  481. void auto_spline_run();
  482. void auto_circle_movetoedge_start(const Location &circle_center, float radius_m);
  483. void auto_circle_start();
  484. void auto_circle_run();
  485. void auto_nav_guided_start();
  486. void auto_nav_guided_run();
  487. bool auto_loiter_start();
  488. void auto_loiter_run();
  489. uint8_t get_default_auto_yaw_mode(bool rtl);
  490. void set_auto_yaw_mode(uint8_t yaw_mode);
  491. void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle);
  492. void set_auto_yaw_roi(const Location &roi_location);
  493. float get_auto_heading(void);
  494. bool circle_init(void);
  495. void circle_run();
  496. bool guided_init(bool ignore_checks = false);
  497. void guided_pos_control_start();
  498. void guided_vel_control_start();
  499. void guided_posvel_control_start();
  500. void guided_angle_control_start();
  501. bool guided_set_destination(const Vector3f& destination);
  502. bool guided_set_destination(const Location& dest_loc);
  503. void guided_set_velocity(const Vector3f& velocity);
  504. bool guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity);
  505. void guided_set_angle(const Quaternion &q, float climb_rate_cms);
  506. void guided_run();
  507. void guided_pos_control_run();
  508. void guided_vel_control_run();
  509. void guided_posvel_control_run();
  510. void guided_angle_control_run();
  511. void guided_limit_clear();
  512. void guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm);
  513. void guided_limit_init_time_and_pos();
  514. bool guided_limit_check();
  515. bool poshold_init(void);
  516. void poshold_run();
  517. bool motordetect_init();
  518. void motordetect_run();
  519. bool stabilize_init(void);
  520. void stabilize_run();
  521. bool manual_init(void);
  522. void manual_run();
  523. void failsafe_sensors_check(void);
  524. void failsafe_crash_check();
  525. void failsafe_ekf_check(void);
  526. void handle_battery_failsafe(const char* type_str, const int8_t action);
  527. void failsafe_gcs_check();
  528. void failsafe_pilot_input_check(void);
  529. void set_neutral_controls(void);
  530. void failsafe_terrain_check();
  531. void failsafe_terrain_set_status(bool data_ok);
  532. void failsafe_terrain_on_event();
  533. void mainloop_failsafe_enable();
  534. void mainloop_failsafe_disable();
  535. void fence_check();
  536. bool set_mode(control_mode_t mode, mode_reason_t reason);
  537. void update_flight_mode();
  538. void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
  539. bool mode_requires_GPS(control_mode_t mode);
  540. bool mode_has_manual_throttle(control_mode_t mode);
  541. bool mode_allows_arming(control_mode_t mode, bool arming_from_gcs);
  542. void notify_flight_mode(control_mode_t mode);
  543. void read_inertia();
  544. void update_surface_and_bottom_detector();
  545. void set_surfaced(bool at_surface);
  546. void set_bottomed(bool at_bottom);
  547. void motors_output();
  548. Vector3f pv_location_to_vector(const Location& loc);
  549. float pv_alt_above_origin(float alt_above_home_cm);
  550. void init_rc_in();
  551. void init_rc_out();
  552. void enable_motor_output();
  553. void init_joystick();
  554. void transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons);
  555. void handle_jsbutton_press(uint8_t button,bool shift=false,bool held=false);
  556. void handle_jsbutton_release(uint8_t button, bool shift);
  557. JSButton* get_button(uint8_t index);
  558. void default_js_buttons(void);
  559. void clear_input_hold();
  560. void read_barometer(void);
  561. void init_rangefinder(void);
  562. void read_rangefinder(void);
  563. bool rangefinder_alt_ok(void);
  564. #if OPTFLOW == ENABLED
  565. void init_optflow();
  566. #endif
  567. void terrain_update();
  568. void terrain_logging();
  569. bool terrain_use();
  570. void init_ardupilot();
  571. void startup_INS_ground();
  572. bool position_ok();
  573. bool ekf_position_ok();
  574. bool optflow_position_ok();
  575. bool should_log(uint32_t mask);
  576. bool start_command(const AP_Mission::Mission_Command& cmd);
  577. bool verify_command(const AP_Mission::Mission_Command& cmd);
  578. bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
  579. bool do_guided(const AP_Mission::Mission_Command& cmd);
  580. void do_nav_wp(const AP_Mission::Mission_Command& cmd);
  581. void do_surface(const AP_Mission::Mission_Command& cmd);
  582. void do_RTL(void);
  583. void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd);
  584. void do_circle(const AP_Mission::Mission_Command& cmd);
  585. void do_loiter_time(const AP_Mission::Mission_Command& cmd);
  586. void do_spline_wp(const AP_Mission::Mission_Command& cmd);
  587. #if NAV_GUIDED == ENABLED
  588. void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
  589. void do_guided_limits(const AP_Mission::Mission_Command& cmd);
  590. #endif
  591. void do_nav_delay(const AP_Mission::Mission_Command& cmd);
  592. void do_wait_delay(const AP_Mission::Mission_Command& cmd);
  593. void do_within_distance(const AP_Mission::Mission_Command& cmd);
  594. void do_yaw(const AP_Mission::Mission_Command& cmd);
  595. void do_change_speed(const AP_Mission::Mission_Command& cmd);
  596. void do_set_home(const AP_Mission::Mission_Command& cmd);
  597. void do_roi(const AP_Mission::Mission_Command& cmd);
  598. void do_mount_control(const AP_Mission::Mission_Command& cmd);
  599. bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
  600. bool verify_surface(const AP_Mission::Mission_Command& cmd);
  601. bool verify_RTL(void);
  602. bool verify_circle(const AP_Mission::Mission_Command& cmd);
  603. bool verify_spline_wp(const AP_Mission::Mission_Command& cmd);
  604. #if NAV_GUIDED == ENABLED
  605. bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd);
  606. #endif
  607. bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
  608. void auto_spline_start(const Location& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location& next_destination);
  609. void log_init(void);
  610. void accel_cal_update(void);
  611. void failsafe_leak_check();
  612. void failsafe_internal_pressure_check();
  613. void failsafe_internal_temperature_check();
  614. void failsafe_terrain_act(void);
  615. bool auto_terrain_recover_start(void);
  616. void auto_terrain_recover_run(void);
  617. void translate_wpnav_rp(float &lateral_out, float &forward_out);
  618. void translate_circle_nav_rp(float &lateral_out, float &forward_out);
  619. void translate_pos_control_rp(float &lateral_out, float &forward_out);
  620. bool surface_init(void);
  621. void surface_run();
  622. uint16_t get_pilot_speed_dn();
  623. void convert_old_parameters(void);
  624. bool handle_do_motor_test(mavlink_command_long_t command);
  625. bool init_motor_test();
  626. bool verify_motor_test();
  627. uint32_t last_do_motor_test_fail_ms = 0;
  628. uint32_t last_do_motor_test_ms = 0;
  629. bool control_check_barometer();
  630. enum Failsafe_Action {
  631. Failsafe_Action_None = 0,
  632. Failsafe_Action_Warn = 1,
  633. Failsafe_Action_Disarm = 2,
  634. Failsafe_Action_Surface = 3
  635. };
  636. static constexpr int8_t _failsafe_priorities[] = {
  637. Failsafe_Action_Disarm,
  638. Failsafe_Action_Surface,
  639. Failsafe_Action_Warn,
  640. Failsafe_Action_None,
  641. -1 // the priority list must end with a sentinel of -1
  642. };
  643. static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1,
  644. "_failsafe_priorities is missing the sentinel");
  645. public:
  646. void mavlink_delay_cb();
  647. void mainloop_failsafe_check();
  648. //------------selfdefine START-----------------------------
  649. control_mode_t control_mode;
  650. mode_reason_t control_mode_reason = MODE_REASON_UNKNOWN;
  651. control_mode_t prev_control_mode;
  652. mode_reason_t prev_control_mode_reason = MODE_REASON_UNKNOWN;
  653. TrackPidClass trackpid;//履带pid控制对象
  654. //------ATOM ------------
  655. float GyroX;//roll角速度
  656. float GyroY;//pitch角速度
  657. float GyroZ;//yaw角速度
  658. float Roll;//roll角度
  659. float Pitch;//pitch角度
  660. float Yaw;//yaw角度
  661. //
  662. uint8_t agl_sec;//机器人俯仰所处于的角度区间
  663. uint8_t agl_act;//机器人当前的姿态动作 水平 or 竖直
  664. //----ATOM---------
  665. unsigned char ucRxBufferATOM[256];//原子九轴接收缓冲区
  666. unsigned char SaberCommandRes[24];//原子配置数据
  667. unsigned char ucRxCnt_atom ;//原子数据接收个数
  668. bool usart_state_atom;//原子九轴通信状态
  669. void updat_Atom(void);//原子九轴数据更新
  670. void GetAngle(void);//计算角度
  671. void uart2_read_Atom(AP_HAL::UARTDriver *uart);//USART2即是temlem2 读取 atom接在temlem2上
  672. void Atom_config(AP_HAL::UARTDriver *uart);//配置
  673. unsigned char Atom_BBC(unsigned char *addr,uint16_t len);//异或校验
  674. float char_to_float(unsigned char u1,unsigned char u2,unsigned char u3,unsigned char u4);
  675. void direction0_90(void);
  676. //------九轴读到的数----------------------
  677. float Roll_Raian;//roll角度弧度
  678. float Pitch_Raian;//pitch角度弧度
  679. float Yaw_Raian;//yaw角度弧度
  680. float Yaw_Angle;//yaw角度,纠正了安装角度
  681. uTof data_floatfromchar;
  682. AP_Motors6DOF motors;
  683. AP_Arming_Sub arming;
  684. AP_Baro barometer;
  685. //灯光
  686. int16_t lights;
  687. //---------USBL ---------------
  688. uint8_t usblpoweroff;
  689. void USBL_PowerSwitch(void);
  690. //-------------------
  691. int16_t yaw_press;//yaw角度给定
  692. void getyaw(void);
  693. void getgain(void);
  694. //---------track----------------
  695. int16_t brushleft;//左毛刷
  696. int16_t brushright;//右毛刷
  697. int16_t motor1_speed_target;//履带电机1 目标PWM
  698. int16_t motor2_speed_target;//履带电机2 目标PWM
  699. float turn_angle;
  700. float track_head_gd;//履带的方位角度给定
  701. uint8_t prepare_state;//水平或者竖直命令
  702. int16_t min_depth;// 最小深度
  703. int16_t max_depth;//最大深度
  704. int16_t autoclean_orgin;//自动洗网开始时,机器人的深度
  705. uint8_t autoclean_step;//自动洗网的阶段:开始 、向上、向下
  706. bool autoclean_flag;//自动洗网状态
  707. bool autoclean_command;//自动洗网状态
  708. bool handclean;
  709. uint8_t clean_mode;
  710. bool clean_bottom_flag;//清洗底网
  711. bool clean_bottom_command;
  712. uint8_t track_motor_arm;//测试履带时的前进2 后退0 停1
  713. PressNetLevel PressLevel;//压力分级枚举类型
  714. float PressLevel_f;//压力分级float类型
  715. int16_t pitch_input_inc;//pitch给定
  716. struct telemetry_info_t {
  717. int16_t dutycycle;
  718. int16_t totalcurrent;
  719. int32_t rpm;// 速度
  720. int32_t amphours;
  721. int32_t watthours;
  722. int16_t toalcurrentIn;
  723. int16_t mottremperature;
  724. int16_t mostemperature;
  725. int16_t voltage;
  726. } _telemetry[OUSHENCAN_MAX_NUM_ESCS];
  727. bool sport_init(void);
  728. void sport_run();
  729. bool clean_init(void);
  730. void clean_run();
  731. void track_reset(void);
  732. void autoclean_flag_chose(void);
  733. void clean_net_joystick(void);
  734. void clean_sidenet_auto(void);
  735. void slowly_speed1(int16_t &p1, int16_t p2,int16_t step,int16_t per) ;
  736. void slowly_speed2(int16_t &p1, int16_t p2,int16_t step,int16_t per) ;
  737. float Constrate1(float d1);
  738. void motor_toCan(void);
  739. void clean_sidenet_state(void);
  740. void clean_sidenet_run(void);
  741. void track_pidcontrol(float _targethead,int16_t &_motor1,int16_t &_motor2);
  742. float get_yaw_error(float yaw_heading);
  743. };
  744. extern const AP_HAL::HAL& hal;
  745. extern Sub sub;
  746. extern AP_HAL::AnalogSource* chan_adc;