Sub.h 33 KB

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