GCS.cpp 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214
  1. #include "GCS.h"
  2. #include <AC_Fence/AC_Fence.h>
  3. #include <AP_BoardConfig/AP_BoardConfig.h>
  4. #include <AP_Logger/AP_Logger.h>
  5. #include <AP_BattMonitor/AP_BattMonitor.h>
  6. #include <AP_Scheduler/AP_Scheduler.h>
  7. #include <AP_Baro/AP_Baro.h>
  8. #include <AP_AHRS/AP_AHRS.h>
  9. extern const AP_HAL::HAL& hal;
  10. void GCS::get_sensor_status_flags(uint32_t &present,
  11. uint32_t &enabled,
  12. uint32_t &health)
  13. {
  14. update_sensor_status_flags();
  15. present = control_sensors_present;
  16. enabled = control_sensors_enabled;
  17. health = control_sensors_health;
  18. }
  19. MissionItemProtocol_Waypoints *GCS::_missionitemprotocol_waypoints;
  20. MissionItemProtocol_Rally *GCS::_missionitemprotocol_rally;
  21. const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = {
  22. MAV_MISSION_TYPE_MISSION,
  23. MAV_MISSION_TYPE_RALLY,
  24. };
  25. /*
  26. send a text message to all GCS
  27. */
  28. void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
  29. {
  30. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  31. hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
  32. send_statustext(severity, GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask(), text);
  33. }
  34. void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
  35. {
  36. va_list arg_list;
  37. va_start(arg_list, fmt);
  38. send_textv(severity, fmt, arg_list);
  39. va_end(arg_list);
  40. }
  41. void GCS::send_to_active_channels(uint32_t msgid, const char *pkt)
  42. {
  43. const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
  44. if (entry == nullptr) {
  45. return;
  46. }
  47. for (uint8_t i=0; i<num_gcs(); i++) {
  48. GCS_MAVLINK &c = *chan(i);
  49. if (!c.is_active()) {
  50. continue;
  51. }
  52. if (entry->max_msg_len + c.packet_overhead() > c.get_uart()->txspace()) {
  53. // no room on this channel
  54. continue;
  55. }
  56. c.send_message(pkt, entry);
  57. }
  58. }
  59. void GCS::send_named_float(const char *name, float value) const
  60. {
  61. mavlink_named_value_float_t packet;
  62. packet.time_boot_ms = AP_HAL::millis();
  63. packet.value = value;
  64. memcpy(packet.name, name, MIN(strlen(name), (uint8_t)MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN));
  65. gcs().send_to_active_channels(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT,
  66. (const char *)&packet);
  67. }
  68. /*
  69. install an alternative protocol handler. This allows another
  70. protocol to take over the link if MAVLink goes idle. It is used to
  71. allow for the AP_BLHeli pass-thru protocols to run on hal.uartA
  72. */
  73. bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
  74. {
  75. if (c >= num_gcs()) {
  76. return false;
  77. }
  78. if (chan(c)->alternative.handler && handler) {
  79. // already have one installed - we may need to add support for
  80. // multiple alternative handlers
  81. return false;
  82. }
  83. chan(c)->alternative.handler = handler;
  84. return true;
  85. }
  86. void GCS::update_sensor_status_flags()
  87. {
  88. control_sensors_present = 0;
  89. control_sensors_enabled = 0;
  90. control_sensors_health = 0;
  91. AP_AHRS &ahrs = AP::ahrs();
  92. const AP_InertialSensor &ins = AP::ins();
  93. control_sensors_present |= MAV_SYS_STATUS_AHRS;
  94. control_sensors_enabled |= MAV_SYS_STATUS_AHRS;
  95. if (!ahrs.initialised() || ahrs.healthy()) {
  96. if (!ahrs.have_inertial_nav() || ins.accel_calibrated_ok_all()) {
  97. control_sensors_health |= MAV_SYS_STATUS_AHRS;
  98. }
  99. }
  100. const Compass &compass = AP::compass();
  101. if (AP::compass().enabled()) {
  102. control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
  103. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
  104. }
  105. if (compass.enabled() && compass.healthy() && ahrs.use_compass()) {
  106. control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
  107. }
  108. const AP_Baro &barometer = AP::baro();
  109. control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  110. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  111. if (barometer.all_healthy()) {
  112. control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
  113. }
  114. const AP_BattMonitor &battery = AP::battery();
  115. control_sensors_present |= MAV_SYS_STATUS_SENSOR_BATTERY;
  116. if (battery.num_instances() > 0) {
  117. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
  118. }
  119. if (battery.healthy() && !battery.has_failsafed()) {
  120. control_sensors_health |= MAV_SYS_STATUS_SENSOR_BATTERY;
  121. }
  122. control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
  123. control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
  124. if (!ins.calibrating()) {
  125. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
  126. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
  127. if (ins.get_accel_health_all()) {
  128. control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
  129. }
  130. if (ins.get_gyro_health_all() && ins.gyro_calibrated_ok_all()) {
  131. control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
  132. }
  133. }
  134. const AP_Logger &logger = AP::logger();
  135. if (logger.logging_present()) { // primary logging only (usually File)
  136. control_sensors_present |= MAV_SYS_STATUS_LOGGING;
  137. }
  138. if (logger.logging_enabled()) {
  139. control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
  140. }
  141. if (!logger.logging_failed()) {
  142. control_sensors_health |= MAV_SYS_STATUS_LOGGING;
  143. }
  144. // set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
  145. control_sensors_present |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
  146. if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
  147. control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
  148. }
  149. control_sensors_health |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
  150. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  151. if (ahrs.get_ekf_type() == 10) {
  152. // always show EKF type 10 as healthy. This prevents spurious error
  153. // messages in xplane and other simulators that use EKF type 10
  154. control_sensors_health |= MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_GPS | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_3D_GYRO;
  155. }
  156. #endif
  157. const AC_Fence *fence = AP::fence();
  158. if (fence != nullptr) {
  159. if (fence->sys_status_enabled()) {
  160. control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
  161. }
  162. if (fence->sys_status_present()) {
  163. control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
  164. }
  165. if (!fence->sys_status_failed()) {
  166. control_sensors_health |= MAV_SYS_STATUS_GEOFENCE;
  167. }
  168. }
  169. update_vehicle_sensor_status_flags();
  170. }
  171. bool GCS::out_of_time() const
  172. {
  173. // while we are in the delay callback we are never out of time:
  174. if (hal.scheduler->in_delay_callback()) {
  175. return false;
  176. }
  177. // we always want to be able to send messages out while in the error loop:
  178. if (AP_BoardConfig::in_sensor_config_error()) {
  179. return false;
  180. }
  181. if (min_loop_time_remaining_for_message_send_us() <= AP::scheduler().time_available_usec()) {
  182. return false;
  183. }
  184. return true;
  185. }