From 89f9b9e9b04a63cc1eb1106e65947f5512b344f4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 15 Dec 2020 21:48:52 +1100 Subject: [PATCH] AP_NavEKF3: use AP_Enum to make code clearer --- libraries/AP_NavEKF/AP_NavEKF_Source.cpp | 40 ++++++++++++------------ libraries/AP_NavEKF/AP_NavEKF_Source.h | 16 +++++----- 2 files changed, 28 insertions(+), 28 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp index 5895a54d01..5b33be67e4 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp @@ -153,11 +153,11 @@ void AP_NavEKF_Source::init() } // initialise active sources - _active_source_set.posxy = (SourceXY)_source_set[0].posxy.get(); - _active_source_set.velxy = (SourceXY)_source_set[0].velxy.get(); - _active_source_set.posz = (SourceZ)_source_set[0].posz.get(); - _active_source_set.velz = (SourceZ)_source_set[0].velz.get(); - _active_source_set.yaw = (SourceYaw)_source_set[0].yaw.get(); + _active_source_set.posxy = _source_set[0].posxy; + _active_source_set.velxy = _source_set[0].velxy; + _active_source_set.posz = _source_set[0].posz; + _active_source_set.velz = _source_set[0].velz; + _active_source_set.yaw = _source_set[0].yaw; initialised = true; } @@ -173,11 +173,11 @@ void AP_NavEKF_Source::setPosVelYawSourceSet(uint8_t source_set_idx) return; } - _active_source_set.posxy = (SourceXY)_source_set[source_set_idx].posxy.get(); - _active_source_set.velxy = (SourceXY)_source_set[source_set_idx].velxy.get(); - _active_source_set.posz = (SourceZ)_source_set[source_set_idx].posz.get(); - _active_source_set.velz = (SourceZ)_source_set[source_set_idx].velz.get(); - _active_source_set.yaw = (SourceYaw)_source_set[source_set_idx].yaw.get(); + _active_source_set.posxy = _source_set[source_set_idx].posxy; + _active_source_set.velxy = _source_set[source_set_idx].velxy; + _active_source_set.posz = _source_set[source_set_idx].posz; + _active_source_set.velz = _source_set[source_set_idx].velz; + _active_source_set.yaw = _source_set[source_set_idx].yaw; } // true/false of whether velocity source should be used @@ -190,7 +190,7 @@ bool AP_NavEKF_Source::useVelXYSource(SourceXY velxy_source) const // check for fuse all velocities if (_options.get() & (uint16_t)(SourceOptions::FUSE_ALL_VELOCITIES)) { for (uint8_t i=0; i posxy; // xy position source + AP_Enum velxy; // xy velocity source + AP_Enum posz; // position z (aka altitude or height) source + AP_Enum velz; // velocity z source + AP_Enum yaw; // yaw source } _source_set[AP_NAKEKF_SOURCE_SET_MAX]; AP_Int16 _options; // source options bitmask