2023-09-02 02:21:36 -03:00
|
|
|
#include "GCS_config.h"
|
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED
|
|
|
|
|
2017-07-08 21:24:43 -03:00
|
|
|
#include "GCS.h"
|
2019-04-26 01:44:34 -03:00
|
|
|
|
2019-08-29 06:26:05 -03:00
|
|
|
#include <AC_Fence/AC_Fence.h>
|
2019-04-26 01:44:34 -03:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2019-04-04 07:49:44 -03:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2019-06-13 19:57:04 -03:00
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
2019-04-26 01:44:34 -03:00
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
2019-06-26 23:32:25 -03:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
2019-08-27 17:07:42 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2022-02-25 01:06:31 -04:00
|
|
|
#include <AP_Compass/AP_Compass.h>
|
2019-11-12 02:16:53 -04:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2019-12-17 18:32:57 -04:00
|
|
|
#include <AP_Arming/AP_Arming.h>
|
2022-02-25 01:06:31 -04:00
|
|
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
2022-02-28 21:19:22 -04:00
|
|
|
#include <AP_Notify/AP_Notify.h>
|
2022-12-14 02:06:36 -04:00
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
2023-07-13 21:58:09 -03:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2024-02-07 00:14:27 -04:00
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2022-02-25 01:06:31 -04:00
|
|
|
|
|
|
|
#include "MissionItemProtocol_Waypoints.h"
|
|
|
|
#include "MissionItemProtocol_Rally.h"
|
|
|
|
#include "MissionItemProtocol_Fence.h"
|
2017-07-08 21:24:43 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2023-12-13 19:20:16 -04:00
|
|
|
void GCS::get_sensor_status_flags(uint32_t &present,
|
|
|
|
uint32_t &enabled,
|
|
|
|
uint32_t &health)
|
|
|
|
{
|
2021-05-25 03:54:21 -03:00
|
|
|
// if this assert fails then fix it and the comment in GCS.h where
|
|
|
|
// _statustext_queue is declared
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
2023-12-13 19:20:16 -04:00
|
|
|
ASSERT_STORAGE_SIZE(GCS::statustext_t, 58);
|
2021-05-25 03:54:21 -03:00
|
|
|
#endif
|
|
|
|
|
2019-02-13 21:59:00 -04:00
|
|
|
update_sensor_status_flags();
|
|
|
|
|
|
|
|
present = control_sensors_present;
|
|
|
|
enabled = control_sensors_enabled;
|
|
|
|
health = control_sensors_health;
|
|
|
|
}
|
|
|
|
|
2022-09-27 20:46:38 -03:00
|
|
|
MissionItemProtocol *GCS::missionitemprotocols[3];
|
2019-04-28 23:52:02 -03:00
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
void GCS::init()
|
|
|
|
{
|
|
|
|
mavlink_system.sysid = sysid_this_mav();
|
|
|
|
}
|
|
|
|
|
2019-08-27 02:15:46 -03:00
|
|
|
/*
|
|
|
|
* returns a mask of channels that statustexts should be sent to
|
|
|
|
*/
|
|
|
|
uint8_t GCS::statustext_send_channel_mask() const
|
|
|
|
{
|
|
|
|
uint8_t ret = 0;
|
|
|
|
ret |= GCS_MAVLINK::active_channel_mask();
|
|
|
|
ret |= GCS_MAVLINK::streaming_channel_mask();
|
|
|
|
ret &= ~GCS_MAVLINK::private_channel_mask();
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2017-07-08 21:24:43 -03:00
|
|
|
/*
|
|
|
|
send a text message to all GCS
|
|
|
|
*/
|
2017-08-01 02:13:34 -03:00
|
|
|
void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list)
|
2017-07-08 21:24:43 -03:00
|
|
|
{
|
2019-08-27 02:15:46 -03:00
|
|
|
uint8_t mask = statustext_send_channel_mask();
|
2019-12-17 21:00:33 -04:00
|
|
|
if (!update_send_has_been_called) {
|
|
|
|
// we have not yet initialised the streaming-channel-mask,
|
|
|
|
// which is done as part of the update() call. So just send
|
|
|
|
// it to all channels:
|
|
|
|
mask = (1<<_num_gcs)-1;
|
|
|
|
}
|
2020-01-12 22:08:14 -04:00
|
|
|
send_textv(severity, fmt, arg_list, mask);
|
2017-08-01 02:13:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
|
|
|
|
{
|
2017-07-08 21:24:43 -03:00
|
|
|
va_list arg_list;
|
|
|
|
va_start(arg_list, fmt);
|
2017-08-01 02:13:34 -03:00
|
|
|
send_textv(severity, fmt, arg_list);
|
2017-07-08 21:24:43 -03:00
|
|
|
va_end(arg_list);
|
|
|
|
}
|
2017-07-08 03:26:34 -03:00
|
|
|
|
2018-11-06 22:11:08 -04:00
|
|
|
void GCS::send_to_active_channels(uint32_t msgid, const char *pkt)
|
|
|
|
{
|
|
|
|
const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
|
|
|
|
if (entry == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<num_gcs(); i++) {
|
2018-12-10 03:56:32 -04:00
|
|
|
GCS_MAVLINK &c = *chan(i);
|
2019-08-27 02:15:46 -03:00
|
|
|
if (c.is_private()) {
|
|
|
|
continue;
|
|
|
|
}
|
2018-11-06 22:11:08 -04:00
|
|
|
if (!c.is_active()) {
|
|
|
|
continue;
|
|
|
|
}
|
2024-03-04 07:59:45 -04:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
if (c.is_high_latency_link) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
#endif
|
2023-02-24 01:02:57 -04:00
|
|
|
// size checks done by this method:
|
2018-11-06 22:11:08 -04:00
|
|
|
c.send_message(pkt, entry);
|
|
|
|
}
|
|
|
|
}
|
2017-07-08 03:26:34 -03:00
|
|
|
|
2018-05-15 02:20:30 -03:00
|
|
|
void GCS::send_named_float(const char *name, float value) const
|
|
|
|
{
|
2018-11-06 22:11:08 -04:00
|
|
|
|
2019-10-16 21:52:53 -03:00
|
|
|
mavlink_named_value_float_t packet {};
|
2018-11-06 22:11:08 -04:00
|
|
|
packet.time_boot_ms = AP_HAL::millis();
|
|
|
|
packet.value = value;
|
|
|
|
memcpy(packet.name, name, MIN(strlen(name), (uint8_t)MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN));
|
|
|
|
|
|
|
|
gcs().send_to_active_channels(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT,
|
|
|
|
(const char *)&packet);
|
2018-05-15 02:20:30 -03:00
|
|
|
}
|
|
|
|
|
2022-01-25 22:51:54 -04:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
void GCS::enable_high_latency_connections(bool enabled)
|
|
|
|
{
|
2022-12-20 20:34:27 -04:00
|
|
|
high_latency_link_enabled = enabled;
|
2022-01-25 22:51:54 -04:00
|
|
|
gcs().send_text(MAV_SEVERITY_NOTICE, "High Latency %s", enabled ? "enabled" : "disabled");
|
|
|
|
}
|
2022-12-20 20:34:27 -04:00
|
|
|
|
|
|
|
bool GCS::get_high_latency_status()
|
|
|
|
{
|
|
|
|
return high_latency_link_enabled;
|
|
|
|
}
|
2022-01-25 22:51:54 -04:00
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
|
2018-03-25 07:45:48 -03:00
|
|
|
/*
|
|
|
|
install an alternative protocol handler. This allows another
|
|
|
|
protocol to take over the link if MAVLink goes idle. It is used to
|
2020-12-10 20:18:38 -04:00
|
|
|
allow for the AP_BLHeli pass-thru protocols to run on hal.serial(0)
|
2018-03-25 07:45:48 -03:00
|
|
|
*/
|
|
|
|
bool GCS::install_alternative_protocol(mavlink_channel_t c, GCS_MAVLINK::protocol_handler_fn_t handler)
|
|
|
|
{
|
2022-12-22 02:29:40 -04:00
|
|
|
GCS_MAVLINK *link = chan(c);
|
|
|
|
if (link == nullptr) {
|
2018-03-25 07:45:48 -03:00
|
|
|
return false;
|
|
|
|
}
|
2022-12-22 02:29:40 -04:00
|
|
|
if (link->alternative.handler && handler) {
|
2018-03-25 07:45:48 -03:00
|
|
|
// already have one installed - we may need to add support for
|
|
|
|
// multiple alternative handlers
|
|
|
|
return false;
|
|
|
|
}
|
2022-12-22 02:29:40 -04:00
|
|
|
link->alternative.handler = handler;
|
2018-03-25 07:45:48 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-02-19 19:01:16 -04:00
|
|
|
void GCS::update_sensor_status_flags()
|
|
|
|
{
|
|
|
|
control_sensors_present = 0;
|
|
|
|
control_sensors_enabled = 0;
|
|
|
|
control_sensors_health = 0;
|
|
|
|
|
2023-06-20 05:38:59 -03:00
|
|
|
#if AP_INERTIALSENSOR_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
const AP_InertialSensor &ins = AP::ins();
|
2023-06-20 05:38:59 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AP_AHRS_ENABLED && AP_INERTIALSENSOR_ENABLED
|
|
|
|
AP_AHRS &ahrs = AP::ahrs();
|
2019-02-19 19:01:16 -04:00
|
|
|
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_AHRS;
|
2021-02-12 20:26:15 -04:00
|
|
|
if (ahrs.initialised()) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_AHRS;
|
|
|
|
if (ahrs.healthy()) {
|
|
|
|
if (!ahrs.have_inertial_nav() || ins.accel_calibrated_ok_all()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_AHRS;
|
|
|
|
}
|
2019-02-19 19:01:16 -04:00
|
|
|
}
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-04-13 20:34:58 -03:00
|
|
|
|
2023-06-20 03:36:07 -03:00
|
|
|
#if AP_COMPASS_ENABLED
|
2019-04-13 20:34:58 -03:00
|
|
|
const Compass &compass = AP::compass();
|
2021-07-27 21:27:38 -03:00
|
|
|
if (AP::compass().available()) {
|
2019-04-13 20:34:58 -03:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
|
|
}
|
2021-07-27 21:27:38 -03:00
|
|
|
if (compass.available() && compass.healthy()) {
|
2019-04-13 20:34:58 -03:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-02-19 19:01:16 -04:00
|
|
|
|
2023-06-20 03:50:04 -03:00
|
|
|
#if AP_BARO_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
const AP_Baro &barometer = AP::baro();
|
2023-09-18 05:48:01 -03:00
|
|
|
if (barometer.num_instances() > 0) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
if (barometer.all_healthy()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
|
|
|
}
|
2019-02-19 19:01:16 -04:00
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-02-19 19:01:16 -04:00
|
|
|
|
2023-06-20 03:40:34 -03:00
|
|
|
#if AP_GPS_ENABLED
|
2019-11-08 02:58:57 -04:00
|
|
|
const AP_GPS &gps = AP::gps();
|
|
|
|
if (gps.status() > AP_GPS::NO_GPS) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
|
|
}
|
|
|
|
if (gps.is_healthy() && gps.status() >= min_status_for_gps_healthy()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-11-08 02:58:57 -04:00
|
|
|
|
2023-06-20 03:08:15 -03:00
|
|
|
#if AP_BATTERY_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
const AP_BattMonitor &battery = AP::battery();
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
|
|
if (battery.num_instances() > 0) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
|
|
}
|
|
|
|
if (battery.healthy() && !battery.has_failsafed()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_BATTERY;
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-02-19 19:01:16 -04:00
|
|
|
|
2023-06-20 05:38:59 -03:00
|
|
|
#if AP_INERTIALSENSOR_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
|
|
|
if (!ins.calibrating()) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
|
|
|
|
if (ins.get_accel_health_all()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
|
|
|
}
|
|
|
|
if (ins.get_gyro_health_all() && ins.gyro_calibrated_ok_all()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
|
|
|
|
}
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-02-19 19:01:16 -04:00
|
|
|
|
2021-11-23 03:52:01 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
const AP_Logger &logger = AP::logger();
|
2021-11-23 03:52:01 -04:00
|
|
|
bool logging_present = logger.logging_present();
|
|
|
|
bool logging_enabled = logger.logging_enabled();
|
|
|
|
bool logging_healthy = !logger.logging_failed();
|
2023-06-20 03:40:34 -03:00
|
|
|
#if AP_GPS_ENABLED
|
2021-11-23 03:52:01 -04:00
|
|
|
// some GPS units do logging, so they have to be healthy too:
|
|
|
|
logging_present |= gps.logging_present();
|
|
|
|
logging_enabled |= gps.logging_enabled();
|
|
|
|
logging_healthy &= !gps.logging_failed();
|
|
|
|
#endif
|
|
|
|
if (logging_present) {
|
2019-02-19 19:01:16 -04:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
2021-11-23 03:52:01 -04:00
|
|
|
if (logging_enabled) {
|
2019-02-19 19:01:16 -04:00
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
2021-11-23 03:52:01 -04:00
|
|
|
if (logging_healthy) {
|
2019-02-19 19:01:16 -04:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_LOGGING;
|
|
|
|
}
|
2021-11-23 03:52:01 -04:00
|
|
|
#endif // HAL_LOGGING_ENABLED
|
2019-02-19 19:01:16 -04:00
|
|
|
|
|
|
|
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
|
2021-07-11 03:40:22 -03:00
|
|
|
#if !defined(HAL_BUILD_AP_PERIPH)
|
2019-02-19 19:01:16 -04:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
|
|
|
|
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
|
|
|
|
}
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-02-19 19:01:16 -04:00
|
|
|
|
2024-01-10 18:16:57 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_AHRS_ENABLED
|
2019-06-21 22:26:30 -03:00
|
|
|
if (ahrs.get_ekf_type() == 10) {
|
|
|
|
// always show EKF type 10 as healthy. This prevents spurious error
|
|
|
|
// messages in xplane and other simulators that use EKF type 10
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_GPS | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_3D_GYRO;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2023-01-04 17:41:28 -04:00
|
|
|
#if AP_FENCE_ENABLED
|
2019-08-29 06:26:05 -03:00
|
|
|
const AC_Fence *fence = AP::fence();
|
|
|
|
if (fence != nullptr) {
|
|
|
|
if (fence->sys_status_enabled()) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_GEOFENCE;
|
|
|
|
}
|
|
|
|
if (fence->sys_status_present()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_GEOFENCE;
|
|
|
|
}
|
|
|
|
if (!fence->sys_status_failed()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_GEOFENCE;
|
|
|
|
}
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-08-29 06:26:05 -03:00
|
|
|
|
2021-10-05 00:19:46 -03:00
|
|
|
// airspeed
|
|
|
|
#if AP_AIRSPEED_ENABLED
|
|
|
|
const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
|
|
|
|
if (airspeed && airspeed->enabled()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
2022-01-26 02:37:29 -04:00
|
|
|
const bool use = airspeed->use();
|
2024-01-10 18:16:57 -04:00
|
|
|
#if AP_AHRS_ENABLED
|
2022-01-26 02:37:29 -04:00
|
|
|
const bool enabled = AP::ahrs().airspeed_sensor_enabled();
|
2024-01-10 18:16:57 -04:00
|
|
|
#else
|
|
|
|
const AP_Airspeed *_airspeed = AP::airspeed();
|
|
|
|
const bool enabled = (_airspeed != nullptr && _airspeed->use());
|
|
|
|
#endif
|
2022-01-26 02:37:29 -04:00
|
|
|
if (use) {
|
2021-10-05 00:19:46 -03:00
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
|
|
|
}
|
2022-01-26 02:37:29 -04:00
|
|
|
if (airspeed->all_healthy() && (!use || enabled)) {
|
2021-10-05 00:19:46 -03:00
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2022-10-19 00:35:27 -03:00
|
|
|
#if AP_OPTICALFLOW_ENABLED
|
|
|
|
const AP_OpticalFlow *optflow = AP::opticalflow();
|
|
|
|
if (optflow && optflow->enabled()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
|
|
|
}
|
|
|
|
if (optflow && optflow->healthy()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2020-04-06 01:10:49 -03:00
|
|
|
#if HAL_VISUALODOM_ENABLED
|
|
|
|
const AP_VisualOdom *visual_odom = AP::visualodom();
|
|
|
|
if (visual_odom && visual_odom->enabled()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
if (visual_odom->healthy()) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-12-17 18:32:57 -04:00
|
|
|
// give GCS status of prearm checks. This is enabled if any arming checks are enabled.
|
|
|
|
// it is healthy if armed or checks are passing
|
2024-02-23 04:52:05 -04:00
|
|
|
#if AP_ARMING_ENABLED
|
2019-12-17 18:32:57 -04:00
|
|
|
control_sensors_present |= MAV_SYS_STATUS_PREARM_CHECK;
|
|
|
|
if (AP::arming().get_enabled_checks()) {
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_PREARM_CHECK;
|
|
|
|
if (hal.util->get_soft_armed() || AP_Notify::flags.pre_arm_check) {
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_PREARM_CHECK;
|
|
|
|
}
|
|
|
|
}
|
2021-07-11 03:40:22 -03:00
|
|
|
#endif
|
2019-12-17 18:32:57 -04:00
|
|
|
|
2024-02-07 00:14:27 -04:00
|
|
|
#if AP_RC_CHANNEL_ENABLED
|
|
|
|
if (rc().has_ever_seen_rc_input()) {
|
|
|
|
control_sensors_present |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
|
|
|
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
|
|
|
if (!rc().in_rc_failsafe()) { // should this be has_valid_input?
|
|
|
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-02-19 19:01:16 -04:00
|
|
|
update_vehicle_sensor_status_flags();
|
|
|
|
}
|
2019-04-26 01:44:34 -03:00
|
|
|
|
|
|
|
bool GCS::out_of_time() const
|
|
|
|
{
|
2021-07-11 03:40:22 -03:00
|
|
|
#if defined(HAL_BUILD_AP_PERIPH)
|
|
|
|
// we are never out of time for AP_Periph
|
|
|
|
// as we don't have concept of AP_Scheduler in AP_Periph
|
|
|
|
return false;
|
|
|
|
#endif
|
2019-04-26 01:44:34 -03:00
|
|
|
// while we are in the delay callback we are never out of time:
|
|
|
|
if (hal.scheduler->in_delay_callback()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// we always want to be able to send messages out while in the error loop:
|
2019-11-06 18:23:03 -04:00
|
|
|
if (AP_BoardConfig::in_config_error()) {
|
2019-04-26 01:44:34 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (min_loop_time_remaining_for_message_send_us() <= AP::scheduler().time_available_usec()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
2020-04-14 08:08:54 -03:00
|
|
|
|
2022-07-08 03:27:11 -03:00
|
|
|
void gcs_out_of_space_to_send(mavlink_channel_t chan)
|
2020-04-14 08:08:54 -03:00
|
|
|
{
|
2022-12-22 02:31:50 -04:00
|
|
|
GCS_MAVLINK *link = gcs().chan(chan);
|
|
|
|
if (link == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
link->out_of_space_to_send();
|
2020-04-14 08:08:54 -03:00
|
|
|
}
|
2023-01-05 19:33:51 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
check there is enough space for a message
|
|
|
|
*/
|
|
|
|
bool GCS_MAVLINK::check_payload_size(uint16_t max_payload_len)
|
|
|
|
{
|
|
|
|
if (txspace() < unsigned(packet_overhead()+max_payload_len)) {
|
|
|
|
gcs_out_of_space_to_send(chan);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
2023-09-02 02:21:36 -03:00
|
|
|
|
|
|
|
#endif // HAL_GCS_ENABLED
|