mirror of https://github.com/ArduPilot/ardupilot
67 lines
2.1 KiB
C++
67 lines
2.1 KiB
C++
#include "GCS_Tracker.h"
|
|
#include "Tracker.h"
|
|
|
|
uint8_t GCS_Tracker::sysid_this_mav() const
|
|
{
|
|
return tracker.g.sysid_this_mav;
|
|
}
|
|
|
|
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;
|
|
}
|
|
|
|
// avoid building/linking LTM:
|
|
void AP_LTM_Telem::init() {};
|
|
#if AP_DEVO_TELEM_ENABLED
|
|
// avoid building/linking Devo:
|
|
void AP_DEVO_Telem::init() {};
|
|
#endif
|