ArduSub.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360
  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. // ArduSub scheduling, originally copied from ArduCopter
  14. #include "Sub.h"
  15. #define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(Sub, &sub, func, rate_hz, max_time_micros)
  16. /*
  17. scheduler table for fast CPUs - all regular tasks apart from the fast_loop()
  18. should be listed here, along with how often they should be called (in hz)
  19. and the maximum time they are expected to take (in microseconds)
  20. */
  21. const AP_Scheduler::Task Sub::scheduler_tasks[] = {
  22. SCHED_TASK(fifty_hz_loop, 50, 75),
  23. SCHED_TASK(update_GPS, 50, 200),
  24. #if OPTFLOW == ENABLED
  25. SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160),
  26. #endif
  27. SCHED_TASK(update_batt_compass, 10, 120),
  28. SCHED_TASK(read_rangefinder, 20, 100),
  29. SCHED_TASK(update_altitude, 10, 100),
  30. SCHED_TASK(three_hz_loop, 3, 75),
  31. SCHED_TASK(update_turn_counter, 10, 50),
  32. SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
  33. SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
  34. SCHED_TASK(one_hz_loop, 1, 100),
  35. SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180),
  36. SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 250, 1000),
  37. #if MOUNT == ENABLED
  38. SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75),
  39. #endif
  40. #if CAMERA == ENABLED
  41. SCHED_TASK_CLASS(AP_Camera, &sub.camera, update_trigger, 50, 75),
  42. #endif
  43. SCHED_TASK(ten_hz_logging_loop, 10, 350),
  44. SCHED_TASK(twentyfive_hz_logging, 25, 110),
  45. SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300),
  46. SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50),
  47. SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75),
  48. #if RPM_ENABLED == ENABLED
  49. SCHED_TASK(rpm_update, 10, 200),
  50. #endif
  51. SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100),
  52. SCHED_TASK(accel_cal_update, 10, 100),
  53. SCHED_TASK(terrain_update, 10, 100),
  54. #if GRIPPER_ENABLED == ENABLED
  55. SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),
  56. #endif
  57. #ifdef USERHOOK_FASTLOOP
  58. SCHED_TASK(userhook_FastLoop, 100, 75),
  59. #endif
  60. #ifdef USERHOOK_50HZLOOP
  61. SCHED_TASK(userhook_50Hz, 50, 75),
  62. #endif
  63. #ifdef USERHOOK_MEDIUMLOOP
  64. SCHED_TASK(userhook_MediumLoop, 10, 75),
  65. #endif
  66. #ifdef USERHOOK_SLOWLOOP
  67. SCHED_TASK(userhook_SlowLoop, 3.3, 75),
  68. #endif
  69. #ifdef USERHOOK_SUPERSLOWLOOP
  70. SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
  71. #endif
  72. };
  73. constexpr int8_t Sub::_failsafe_priorities[5];
  74. void Sub::setup()
  75. {
  76. // Load the default values of variables listed in var_info[]s
  77. AP_Param::setup_sketch_defaults();
  78. init_ardupilot();
  79. // initialise the main loop scheduler
  80. scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM);
  81. }
  82. void Sub::loop()
  83. {
  84. scheduler.loop();
  85. G_Dt = scheduler.get_loop_period_s();
  86. }
  87. // Main loop - 400hz
  88. void Sub::fast_loop()
  89. {
  90. // update INS immediately to get current gyro data populated
  91. ins.update();
  92. //don't run rate controller in manual or motordetection modes
  93. if (control_mode != MANUAL && control_mode != MOTOR_DETECT&& control_mode != CLEAN) {
  94. // run low level rate controllers that only require IMU data
  95. attitude_control.rate_controller_run();
  96. }
  97. // send outputs to the motors library
  98. motors_output();
  99. // run EKF state estimator (expensive)
  100. // --------------------
  101. read_AHRS();
  102. // Inertial Nav
  103. // --------------------
  104. read_inertia();
  105. // check if ekf has reset target heading
  106. check_ekf_yaw_reset();
  107. // run the attitude controllers
  108. update_flight_mode();
  109. motor_toCan();
  110. // update home from EKF if necessary
  111. update_home_from_EKF();
  112. // check if we've reached the surface or bottom
  113. update_surface_and_bottom_detector();
  114. #if MOUNT == ENABLED
  115. // camera mount's fast update
  116. camera_mount.update_fast();
  117. #endif
  118. // log sensor health
  119. if (should_log(MASK_LOG_ANY)) {
  120. Log_Sensor_Health();
  121. }
  122. }
  123. // 50 Hz tasks
  124. void Sub::fifty_hz_loop()
  125. {
  126. // check pilot input failsafe
  127. failsafe_pilot_input_check();
  128. failsafe_crash_check();
  129. failsafe_ekf_check();
  130. failsafe_sensors_check();
  131. // Update rc input/output
  132. rc().read_input();
  133. SRV_Channels::output_ch_all();
  134. }
  135. // update_batt_compass - read battery and compass
  136. // should be called at 10hz
  137. void Sub::update_batt_compass()
  138. {
  139. // read battery before compass because it may be used for motor interference compensation
  140. battery.read();
  141. if (AP::compass().enabled()) {
  142. // update compass with throttle value - used for compassmot
  143. compass.set_throttle(motors.get_throttle());
  144. compass.read();
  145. }
  146. }
  147. // ten_hz_logging_loop
  148. // should be run at 10hz
  149. void Sub::ten_hz_logging_loop()
  150. {
  151. // log attitude data if we're not already logging at the higher rate
  152. if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
  153. Log_Write_Attitude();
  154. logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
  155. if (should_log(MASK_LOG_PID)) {
  156. logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
  157. logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
  158. logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
  159. logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
  160. }
  161. }
  162. if (should_log(MASK_LOG_MOTBATT)) {
  163. Log_Write_MotBatt();
  164. }
  165. if (should_log(MASK_LOG_RCIN)) {
  166. logger.Write_RCIN();
  167. }
  168. if (should_log(MASK_LOG_RCOUT)) {
  169. logger.Write_RCOUT();
  170. }
  171. if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
  172. pos_control.write_log();
  173. }
  174. if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
  175. logger.Write_Vibration();
  176. }
  177. if (should_log(MASK_LOG_CTUN)) {
  178. attitude_control.control_monitor_log();
  179. }
  180. }
  181. // twentyfive_hz_logging_loop
  182. // should be run at 25hz
  183. void Sub::twentyfive_hz_logging()
  184. {
  185. if (should_log(MASK_LOG_ATTITUDE_FAST)) {
  186. Log_Write_Attitude();
  187. logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
  188. if (should_log(MASK_LOG_PID)) {
  189. logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
  190. logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
  191. logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
  192. logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
  193. }
  194. }
  195. // log IMU data if we're not already logging at the higher rate
  196. if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) {
  197. logger.Write_IMU();
  198. }
  199. }
  200. // three_hz_loop - 3.3hz loop
  201. void Sub::three_hz_loop()
  202. {
  203. leak_detector.update();
  204. failsafe_leak_check();
  205. failsafe_internal_pressure_check();
  206. failsafe_internal_temperature_check();
  207. // check if we've lost contact with the ground station
  208. failsafe_gcs_check();
  209. // check if we've lost terrain data
  210. failsafe_terrain_check();
  211. #if AC_FENCE == ENABLED
  212. // check if we have breached a fence
  213. fence_check();
  214. #endif // AC_FENCE_ENABLED
  215. ServoRelayEvents.update_events();
  216. }
  217. // one_hz_loop - runs at 1Hz
  218. void Sub::one_hz_loop()
  219. {
  220. bool arm_check = arming.pre_arm_checks(false);
  221. ap.pre_arm_check = arm_check;
  222. AP_Notify::flags.pre_arm_check = arm_check;
  223. AP_Notify::flags.pre_arm_gps_check = position_ok();
  224. AP_Notify::flags.flying = motors.armed();
  225. if (should_log(MASK_LOG_ANY)) {
  226. Log_Write_Data(DATA_AP_STATE, ap.value);
  227. }
  228. if (!motors.armed()) {
  229. // make it possible to change ahrs orientation at runtime during initial config
  230. ahrs.update_orientation();
  231. // set all throttle channel settings
  232. motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
  233. }
  234. // update assigned functions and enable auxiliary servos
  235. SRV_Channels::enable_aux_servos();
  236. // update position controller alt limits
  237. update_poscon_alt_max();
  238. // log terrain data
  239. terrain_logging();
  240. // need to set "likely flying" when armed to allow for compass
  241. // learning to run
  242. ahrs.set_likely_flying(hal.util->get_soft_armed());
  243. }
  244. // called at 50hz
  245. void Sub::update_GPS()
  246. {
  247. static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message
  248. bool gps_updated = false;
  249. gps.update();
  250. // log after every gps message
  251. for (uint8_t i=0; i<gps.num_sensors(); i++) {
  252. if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
  253. last_gps_reading[i] = gps.last_message_time_ms(i);
  254. gps_updated = true;
  255. break;
  256. }
  257. }
  258. if (gps_updated) {
  259. #if CAMERA == ENABLED
  260. camera.update();
  261. #endif
  262. }
  263. }
  264. void Sub::read_AHRS()
  265. {
  266. // Perform IMU calculations and get attitude info
  267. //-----------------------------------------------
  268. // <true> tells AHRS to skip INS update as we have already done it in fast_loop()
  269. ahrs.update(true);
  270. ahrs_view.update(true);
  271. }
  272. // read baro and rangefinder altitude at 10hz
  273. void Sub::update_altitude()
  274. {
  275. // read in baro altitude
  276. read_barometer();
  277. //float depth_now =barometer.get_altitude();
  278. //gcs().send_text(MAV_SEVERITY_INFO, "Depth sensor is %f.",depth_now);
  279. if (should_log(MASK_LOG_CTUN)) {
  280. Log_Write_Control_Tuning();
  281. }
  282. }
  283. bool Sub::control_check_barometer()
  284. {
  285. #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
  286. if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor
  287. gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected.");
  288. return false;
  289. } else if (failsafe.sensor_health) {
  290. gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error.");
  291. return false;
  292. }
  293. #endif
  294. return true;
  295. }
  296. AP_HAL_MAIN_CALLBACKS(&sub);