sensors.cpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  1. #include "Sub.h"
  2. // return barometric altitude in centimeters
  3. void Sub::read_barometer()
  4. {
  5. barometer.update();
  6. // If we are reading a positive altitude, the sensor needs calibration
  7. // Even a few meters above the water we should have no significant depth reading
  8. if(!motors.armed() && barometer.get_altitude() > 0) {
  9. barometer.update_calibration();
  10. }
  11. if (ap.depth_sensor_present) {
  12. sensor_health.depth = barometer.healthy(depth_sensor_idx);
  13. }
  14. }
  15. void Sub::init_rangefinder()
  16. {
  17. #if RANGEFINDER_ENABLED == ENABLED
  18. rangefinder.init(ROTATION_PITCH_270);
  19. rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);
  20. rangefinder_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_270);
  21. #endif
  22. }
  23. // return rangefinder altitude in centimeters
  24. void Sub::read_rangefinder()
  25. {
  26. #if RANGEFINDER_ENABLED == ENABLED
  27. rangefinder.update();
  28. rangefinder_state.alt_healthy = ((rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) && (rangefinder.range_valid_count_orient(ROTATION_PITCH_270) >= RANGEFINDER_HEALTH_MAX));
  29. int16_t temp_alt = rangefinder.distance_cm_orient(ROTATION_PITCH_270);
  30. #if RANGEFINDER_TILT_CORRECTION == ENABLED
  31. // correct alt for angle of the rangefinder
  32. temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
  33. #endif
  34. rangefinder_state.alt_cm = temp_alt;
  35. // filter rangefinder for use by AC_WPNav
  36. uint32_t now = AP_HAL::millis();
  37. if (rangefinder_state.alt_healthy) {
  38. if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {
  39. // reset filter if we haven't used it within the last second
  40. rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
  41. } else {
  42. rangefinder_state.alt_cm_filt.apply(rangefinder_state.alt_cm, 0.05f);
  43. }
  44. rangefinder_state.last_healthy_ms = now;
  45. }
  46. // send rangefinder altitude and health to waypoint navigation library
  47. wp_nav.set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
  48. #else
  49. rangefinder_state.enabled = false;
  50. rangefinder_state.alt_healthy = false;
  51. rangefinder_state.alt_cm = 0;
  52. #endif
  53. }
  54. // return true if rangefinder_alt can be used
  55. bool Sub::rangefinder_alt_ok()
  56. {
  57. return (rangefinder_state.enabled && rangefinder_state.alt_healthy);
  58. }
  59. /*
  60. update RPM sensors
  61. */
  62. #if RPM_ENABLED == ENABLED
  63. void Sub::rpm_update(void)
  64. {
  65. rpm_sensor.update();
  66. if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
  67. if (should_log(MASK_LOG_RCIN)) {
  68. logger.Write_RPM(rpm_sensor);
  69. }
  70. }
  71. }
  72. #endif
  73. // initialise optical flow sensor
  74. #if OPTFLOW == ENABLED
  75. void Sub::init_optflow()
  76. {
  77. // initialise optical flow sensor
  78. optflow.init(MASK_LOG_OPTFLOW);
  79. }
  80. #endif // OPTFLOW == ENABLED
  81. void Sub::accel_cal_update()
  82. {
  83. if (hal.util->get_soft_armed()) {
  84. return;
  85. }
  86. ins.acal_update();
  87. // check if new trim values, and set them
  88. float trim_roll, trim_pitch;
  89. if (ins.get_new_trim(trim_roll, trim_pitch)) {
  90. ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
  91. }
  92. }