Files
ardupilot/AntennaTracker/GCS_Tracker.cpp
Peter Barker 7a899ec464 AntennaTracker: create and use MAV_ parameter namespace
Move serveral parameters in
2025-04-07 10:58:41 +10:00

64 lines
2.0 KiB
C++

#include "GCS_Tracker.h"
#include "Tracker.h"
void GCS_Tracker::request_datastream_position(const uint8_t _sysid, const uint8_t compid)
{
for (uint8_t i=0; i < num_gcs(); i++) {
// request position
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) {
mavlink_msg_request_data_stream_send(
(mavlink_channel_t)i,
_sysid,
compid,
MAV_DATA_STREAM_POSITION,
tracker.g.mavlink_update_rate,
1); // start streaming
}
}
}
void GCS_Tracker::request_datastream_airpressure(const uint8_t _sysid, const uint8_t compid)
{
for (uint8_t i=0; i < num_gcs(); i++) {
// request air pressure
if (HAVE_PAYLOAD_SPACE((mavlink_channel_t)i, DATA_STREAM)) {
mavlink_msg_request_data_stream_send(
(mavlink_channel_t)i,
_sysid,
compid,
MAV_DATA_STREAM_RAW_SENSORS,
tracker.g.mavlink_update_rate,
1); // start streaming
}
}
}
// update sensors and subsystems present, enabled and healthy flags for reporting to GCS
void GCS_Tracker::update_vehicle_sensor_status_flags()
{
// default sensors present
control_sensors_present |=
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
control_sensors_enabled |=
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
control_sensors_health |=
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
}
#if AP_LTM_TELEM_ENABLED
// avoid building/linking LTM:
void AP_LTM_Telem::init() {};
#endif
#if AP_DEVO_TELEM_ENABLED
// avoid building/linking Devo:
void AP_DEVO_Telem::init() {};
#endif