mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
cc39e36ee1
commit
53eb2f2bf4
|
@ -572,7 +572,7 @@ uint8_t NavEKF2_core::getFramesSincePredict(void) const
|
|||
}
|
||||
|
||||
// return true when external nav data is also being used as a yaw observation
|
||||
bool NavEKF2_core::isExtNavUsedForYaw()
|
||||
bool NavEKF2_core::isExtNavUsedForYaw() const
|
||||
{
|
||||
return extNavUsedForYaw;
|
||||
}
|
||||
|
|
|
@ -309,7 +309,7 @@ public:
|
|||
void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);
|
||||
|
||||
// return true when external nav data is also being used as a yaw observation
|
||||
bool isExtNavUsedForYaw(void);
|
||||
bool isExtNavUsedForYaw(void) const;
|
||||
|
||||
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
||||
void writeDefaultAirSpeed(float airspeed);
|
||||
|
|
Loading…
Reference in New Issue