1 #include "GCS_Tracker.h"
4 uint8_t GCS_Tracker::sysid_this_mav() const
6 return tracker
.g
.sysid_this_mav
;
9 void GCS_Tracker::request_datastream_position(const uint8_t sysid
, const uint8_t compid
)
11 for (uint8_t i
=0; i
< num_gcs(); i
++) {
13 if (HAVE_PAYLOAD_SPACE((mavlink_channel_t
)i
, DATA_STREAM
)) {
14 mavlink_msg_request_data_stream_send(
18 MAV_DATA_STREAM_POSITION
,
19 tracker
.g
.mavlink_update_rate
,
20 1); // start streaming
25 void GCS_Tracker::request_datastream_airpressure(const uint8_t sysid
, const uint8_t compid
)
27 for (uint8_t i
=0; i
< num_gcs(); i
++) {
28 // request air pressure
29 if (HAVE_PAYLOAD_SPACE((mavlink_channel_t
)i
, DATA_STREAM
)) {
30 mavlink_msg_request_data_stream_send(
34 MAV_DATA_STREAM_RAW_SENSORS
,
35 tracker
.g
.mavlink_update_rate
,
36 1); // start streaming
41 // update sensors and subsystems present, enabled and healthy flags for reporting to GCS
42 void GCS_Tracker::update_vehicle_sensor_status_flags()
44 // default sensors present
45 control_sensors_present
|=
46 MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL
|
47 MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION
|
48 MAV_SYS_STATUS_SENSOR_YAW_POSITION
;
50 control_sensors_enabled
|=
51 MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL
|
52 MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION
|
53 MAV_SYS_STATUS_SENSOR_YAW_POSITION
;
55 control_sensors_health
|=
56 MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL
|
57 MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION
|
58 MAV_SYS_STATUS_SENSOR_YAW_POSITION
;
61 #if AP_LTM_TELEM_ENABLED
62 // avoid building/linking LTM:
63 void AP_LTM_Telem::init() {};
65 #if AP_DEVO_TELEM_ENABLED
66 // avoid building/linking Devo:
67 void AP_DEVO_Telem::init() {};