-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathGCS_Tracker.cpp
68 lines (60 loc) · 2.25 KB
/
GCS_Tracker.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
#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;
// first what sensors/controllers we have
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()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
}
// avoid building/linking Devo:
void AP_DEVO_Telem::init() {};