Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/GCS_Copter.cpp
9437 views
1
#include "GCS_Copter.h"
2
3
#include "Copter.h"
4
5
const char* GCS_Copter::frame_string() const
6
{
7
if (copter.motors == nullptr) {
8
return "MultiCopter";
9
}
10
return copter.motors->get_frame_string();
11
}
12
13
bool GCS_Copter::simple_input_active() const
14
{
15
return copter.simple_mode == Copter::SimpleMode::SIMPLE;
16
}
17
18
bool GCS_Copter::supersimple_input_active() const
19
{
20
return copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE;
21
}
22
23
void GCS_Copter::update_vehicle_sensor_status_flags(void)
24
{
25
control_sensors_present |=
26
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
27
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
28
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
29
30
control_sensors_enabled |=
31
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
32
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
33
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
34
35
control_sensors_health |=
36
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL |
37
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION |
38
MAV_SYS_STATUS_SENSOR_YAW_POSITION;
39
40
// Update position controller flags
41
if (copter.pos_control != nullptr) {
42
control_sensors_present |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
43
control_sensors_present |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
44
45
// XY position controller
46
if (copter.pos_control->NE_is_active()) {
47
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
48
control_sensors_health |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
49
}
50
51
// Z altitude controller
52
if (copter.pos_control->D_is_active()) {
53
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
54
control_sensors_health |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
55
}
56
}
57
58
// optional sensors, some of which are essentially always
59
// available in the firmware:
60
#if HAL_PROXIMITY_ENABLED
61
if (copter.g2.proximity.sensor_present()) {
62
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
63
}
64
if (copter.g2.proximity.sensor_enabled()) {
65
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
66
}
67
if (!copter.g2.proximity.sensor_failed()) {
68
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROXIMITY;
69
}
70
#endif
71
72
#if AP_RANGEFINDER_ENABLED
73
const RangeFinder *rangefinder = RangeFinder::get_singleton();
74
if (rangefinder && rangefinder->has_orientation(ROTATION_PITCH_270)) {
75
control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
76
}
77
if (copter.rangefinder_state.enabled) {
78
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
79
if (rangefinder && rangefinder->has_data_orient(ROTATION_PITCH_270)) {
80
control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
81
}
82
}
83
#endif
84
85
#if AC_PRECLAND_ENABLED
86
if (copter.precland.enabled()) {
87
control_sensors_present |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
88
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
89
}
90
if (copter.precland.enabled() && copter.precland.healthy()) {
91
control_sensors_health |= MAV_SYS_STATUS_SENSOR_VISION_POSITION;
92
}
93
#endif
94
95
#if AP_TERRAIN_AVAILABLE
96
switch (copter.terrain.status()) {
97
case AP_Terrain::TerrainStatusDisabled:
98
break;
99
case AP_Terrain::TerrainStatusUnhealthy:
100
// To-Do: restore unhealthy terrain status reporting once terrain is used in copter
101
//control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
102
//control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
103
//break;
104
case AP_Terrain::TerrainStatusOK:
105
control_sensors_present |= MAV_SYS_STATUS_TERRAIN;
106
control_sensors_enabled |= MAV_SYS_STATUS_TERRAIN;
107
control_sensors_health |= MAV_SYS_STATUS_TERRAIN;
108
break;
109
}
110
#endif
111
112
control_sensors_present |= MAV_SYS_STATUS_SENSOR_PROPULSION;
113
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_PROPULSION;
114
// only mark propulsion healthy if all of the motors are producing
115
// nominal thrust
116
if (!copter.motors->get_thrust_boost()) {
117
control_sensors_health |= MAV_SYS_STATUS_SENSOR_PROPULSION;
118
}
119
}
120
121