ArduSub.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364
  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, 400, 550),
  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. float depth = barometer.get_altitude(); // cm
  93. static int16_t c4 = 0;
  94. c4++;
  95. if(c4>400){
  96. c4 =0 ;
  97. gcs().send_text(MAV_SEVERITY_INFO, "depth %f.",(float)depth);
  98. }
  99. //don't run rate controller in manual or motordetection modes
  100. if (control_mode != MANUAL && control_mode != MOTOR_DETECT&& control_mode != CLEAN) {
  101. // run low level rate controllers that only require IMU data
  102. attitude_control.rate_controller_run();
  103. }
  104. // send outputs to the motors library
  105. motors_output();
  106. // run EKF state estimator (expensive)
  107. // --------------------
  108. read_AHRS();
  109. // Inertial Nav
  110. // --------------------
  111. read_inertia();
  112. // check if ekf has reset target heading
  113. check_ekf_yaw_reset();
  114. // run the attitude controllers
  115. update_flight_mode();
  116. motor_toCan();
  117. // update home from EKF if necessary
  118. update_home_from_EKF();
  119. // check if we've reached the surface or bottom
  120. update_surface_and_bottom_detector();
  121. #if MOUNT == ENABLED
  122. // camera mount's fast update
  123. camera_mount.update_fast();
  124. #endif
  125. // log sensor health
  126. if (should_log(MASK_LOG_ANY)) {
  127. Log_Sensor_Health();
  128. }
  129. }
  130. // 50 Hz tasks
  131. void Sub::fifty_hz_loop()
  132. {
  133. // check pilot input failsafe
  134. failsafe_pilot_input_check();
  135. failsafe_crash_check();
  136. failsafe_ekf_check();
  137. failsafe_sensors_check();
  138. // Update rc input/output
  139. rc().read_input();
  140. SRV_Channels::output_ch_all();
  141. }
  142. // update_batt_compass - read battery and compass
  143. // should be called at 10hz
  144. void Sub::update_batt_compass()
  145. {
  146. // read battery before compass because it may be used for motor interference compensation
  147. battery.read();
  148. if (AP::compass().enabled()) {
  149. // update compass with throttle value - used for compassmot
  150. compass.set_throttle(motors.get_throttle());
  151. compass.read();
  152. }
  153. }
  154. // ten_hz_logging_loop
  155. // should be run at 10hz
  156. void Sub::ten_hz_logging_loop()
  157. {
  158. // log attitude data if we're not already logging at the higher rate
  159. if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
  160. Log_Write_Attitude();
  161. logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
  162. if (should_log(MASK_LOG_PID)) {
  163. logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
  164. logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
  165. logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
  166. logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
  167. }
  168. }
  169. if (should_log(MASK_LOG_MOTBATT)) {
  170. Log_Write_MotBatt();
  171. }
  172. if (should_log(MASK_LOG_RCIN)) {
  173. logger.Write_RCIN();
  174. }
  175. if (should_log(MASK_LOG_RCOUT)) {
  176. logger.Write_RCOUT();
  177. }
  178. if (should_log(MASK_LOG_NTUN) && mode_requires_GPS(control_mode)) {
  179. pos_control.write_log();
  180. }
  181. if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
  182. logger.Write_Vibration();
  183. }
  184. if (should_log(MASK_LOG_CTUN)) {
  185. attitude_control.control_monitor_log();
  186. }
  187. }
  188. // twentyfive_hz_logging_loop
  189. // should be run at 25hz
  190. void Sub::twentyfive_hz_logging()
  191. {
  192. if (should_log(MASK_LOG_ATTITUDE_FAST)) {
  193. Log_Write_Attitude();
  194. logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
  195. if (should_log(MASK_LOG_PID)) {
  196. logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
  197. logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
  198. logger.Write_PID(LOG_PIDY_MSG, attitude_control.get_rate_yaw_pid().get_pid_info());
  199. logger.Write_PID(LOG_PIDA_MSG, pos_control.get_accel_z_pid().get_pid_info());
  200. }
  201. }
  202. // log IMU data if we're not already logging at the higher rate
  203. if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) {
  204. logger.Write_IMU();
  205. }
  206. }
  207. // three_hz_loop - 3.3hz loop
  208. void Sub::three_hz_loop()
  209. {
  210. leak_detector.update();
  211. failsafe_leak_check();
  212. failsafe_internal_pressure_check();
  213. failsafe_internal_temperature_check();
  214. // check if we've lost contact with the ground station
  215. failsafe_gcs_check();
  216. // check if we've lost terrain data
  217. failsafe_terrain_check();
  218. #if AC_FENCE == ENABLED
  219. // check if we have breached a fence
  220. fence_check();
  221. #endif // AC_FENCE_ENABLED
  222. ServoRelayEvents.update_events();
  223. }
  224. // one_hz_loop - runs at 1Hz
  225. void Sub::one_hz_loop()
  226. {
  227. bool arm_check = arming.pre_arm_checks(false);
  228. ap.pre_arm_check = arm_check;
  229. AP_Notify::flags.pre_arm_check = arm_check;
  230. AP_Notify::flags.pre_arm_gps_check = position_ok();
  231. AP_Notify::flags.flying = motors.armed();
  232. if (should_log(MASK_LOG_ANY)) {
  233. Log_Write_Data(DATA_AP_STATE, ap.value);
  234. }
  235. if (!motors.armed()) {
  236. // make it possible to change ahrs orientation at runtime during initial config
  237. ahrs.update_orientation();
  238. // set all throttle channel settings
  239. motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
  240. }
  241. // update assigned functions and enable auxiliary servos
  242. SRV_Channels::enable_aux_servos();
  243. // update position controller alt limits
  244. update_poscon_alt_max();
  245. // log terrain data
  246. terrain_logging();
  247. // need to set "likely flying" when armed to allow for compass
  248. // learning to run
  249. ahrs.set_likely_flying(hal.util->get_soft_armed());
  250. }
  251. // called at 50hz
  252. void Sub::update_GPS()
  253. {
  254. static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message
  255. bool gps_updated = false;
  256. gps.update();
  257. // log after every gps message
  258. for (uint8_t i=0; i<gps.num_sensors(); i++) {
  259. if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
  260. last_gps_reading[i] = gps.last_message_time_ms(i);
  261. gps_updated = true;
  262. break;
  263. }
  264. }
  265. if (gps_updated) {
  266. #if CAMERA == ENABLED
  267. camera.update();
  268. #endif
  269. }
  270. }
  271. void Sub::read_AHRS()
  272. {
  273. // Perform IMU calculations and get attitude info
  274. //-----------------------------------------------
  275. // <true> tells AHRS to skip INS update as we have already done it in fast_loop()
  276. ahrs.update(true);
  277. ahrs_view.update(true);
  278. }
  279. // read baro and rangefinder altitude at 10hz
  280. void Sub::update_altitude()
  281. {
  282. // read in baro altitude
  283. read_barometer();
  284. if (should_log(MASK_LOG_CTUN)) {
  285. Log_Write_Control_Tuning();
  286. }
  287. }
  288. bool Sub::control_check_barometer()
  289. {
  290. #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
  291. if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor
  292. gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected.");
  293. return false;
  294. } else if (failsafe.sensor_health) {
  295. gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error.");
  296. return false;
  297. }
  298. #endif
  299. return true;
  300. }
  301. AP_HAL_MAIN_CALLBACKS(&sub);