GCS_Sub.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103
  1. #include "GCS_Sub.h"
  2. #include "Sub.h"
  3. void GCS_Sub::update_vehicle_sensor_status_flags()
  4. {
  5. control_sensors_present |=
  6. MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
  7. MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
  8. MAV_SYS_STATUS_SENSOR_YAW_POSITION;
  9. control_sensors_enabled |=
  10. MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
  11. MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
  12. MAV_SYS_STATUS_SENSOR_YAW_POSITION;
  13. control_sensors_health |=
  14. MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
  15. MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
  16. MAV_SYS_STATUS_SENSOR_YAW_POSITION;
  17. // first what sensors/controllers we have
  18. if (sub.ap.depth_sensor_present) {
  19. control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  20. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  21. }
  22. const AP_GPS &gps = AP::gps();
  23. if (gps.status() > AP_GPS::NO_GPS) {
  24. control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
  25. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
  26. }
  27. #if OPTFLOW == ENABLED
  28. const OpticalFlow *optflow = AP::opticalflow();
  29. if (optflow && optflow->enabled()) {
  30. control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
  31. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
  32. }
  33. #endif
  34. control_sensors_present |=
  35. MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL |
  36. MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
  37. switch (sub.control_mode) {
  38. case ALT_HOLD:
  39. case AUTO:
  40. case GUIDED:
  41. case CIRCLE:
  42. case SURFACE:
  43. case POSHOLD:
  44. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
  45. control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
  46. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
  47. control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
  48. break;
  49. default:
  50. break;
  51. }
  52. control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; // check the internal barometer only
  53. if (sub.sensor_health.depth) {
  54. control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  55. }
  56. if (gps.is_healthy()) {
  57. control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
  58. }
  59. #if OPTFLOW == ENABLED
  60. if (optflow && optflow->healthy()) {
  61. control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
  62. }
  63. #endif
  64. #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
  65. switch (sub.terrain.status()) {
  66. case AP_Terrain::TerrainStatusDisabled:
  67. break;
  68. case AP_Terrain::TerrainStatusUnhealthy:
  69. // To-Do: restore unhealthy terrain status reporting once terrain is used in Sub
  70. //control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
  71. //control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
  72. //break;
  73. case AP_Terrain::TerrainStatusOK:
  74. control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
  75. control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
  76. control_sensors_health |= MAV_SYS_STATUS_TERRAIN;
  77. break;
  78. }
  79. #endif
  80. #if RANGEFINDER_ENABLED == ENABLED
  81. const RangeFinder *rangefinder = RangeFinder::get_singleton();
  82. if (sub.rangefinder_state.enabled) {
  83. control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
  84. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
  85. if (rangefinder && rangefinder->has_data_orient(ROTATION_PITCH_270)) {
  86. control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
  87. }
  88. }
  89. #endif
  90. }
  91. // avoid building/linking Devo:
  92. void AP_DEVO_Telem::init() {};