mirror of https://github.com/ArduPilot/ardupilot
Plane: add mehtod to check terrain by mode
This commit is contained in:
parent
dc2ba8236a
commit
0549e08c5c
|
@ -798,6 +798,7 @@ private:
|
||||||
bool terrain_disabled();
|
bool terrain_disabled();
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE
|
||||||
bool terrain_enabled_in_current_mode() const;
|
bool terrain_enabled_in_current_mode() const;
|
||||||
|
bool terrain_enabled_in_mode(Mode::Number num) const;
|
||||||
enum class terrain_bitmask {
|
enum class terrain_bitmask {
|
||||||
ALL = 1U << 0,
|
ALL = 1U << 0,
|
||||||
FLY_BY_WIRE_B = 1U << 1,
|
FLY_BY_WIRE_B = 1U << 1,
|
||||||
|
|
|
@ -765,6 +765,11 @@ const Plane::TerrainLookupTable Plane::Terrain_lookup[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
bool Plane::terrain_enabled_in_current_mode() const
|
bool Plane::terrain_enabled_in_current_mode() const
|
||||||
|
{
|
||||||
|
return terrain_enabled_in_mode(control_mode->mode_number());
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Plane::terrain_enabled_in_mode(Mode::Number num) const
|
||||||
{
|
{
|
||||||
// Global enable
|
// Global enable
|
||||||
if ((g.terrain_follow.get() & int32_t(terrain_bitmask::ALL)) != 0) {
|
if ((g.terrain_follow.get() & int32_t(terrain_bitmask::ALL)) != 0) {
|
||||||
|
@ -773,7 +778,7 @@ bool Plane::terrain_enabled_in_current_mode() const
|
||||||
|
|
||||||
// Specific enable
|
// Specific enable
|
||||||
for (const struct TerrainLookupTable entry : Terrain_lookup) {
|
for (const struct TerrainLookupTable entry : Terrain_lookup) {
|
||||||
if (entry.mode_num == control_mode->mode_number()) {
|
if (entry.mode_num == num) {
|
||||||
if ((g.terrain_follow.get() & int32_t(entry.bitmask)) != 0) {
|
if ((g.terrain_follow.get() & int32_t(entry.bitmask)) != 0) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue