mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: rename setPosVelYawSourceSet
This commit is contained in:
parent
5eb3875ebb
commit
8895d20c45
@ -1003,9 +1003,9 @@ void NavEKF3::resetCoreErrors(void)
|
||||
}
|
||||
|
||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||
void NavEKF3::setPosVelYawSource(uint8_t source_set_idx)
|
||||
void NavEKF3::setPosVelYawSourceSet(uint8_t source_set_idx)
|
||||
{
|
||||
sources.setPosVelYawSource(source_set_idx);
|
||||
sources.setPosVelYawSourceSet(source_set_idx);
|
||||
}
|
||||
|
||||
// Check basic filter health metrics and return a consolidated health status
|
||||
|
@ -413,7 +413,7 @@ public:
|
||||
void requestYawReset(void);
|
||||
|
||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||
void setPosVelYawSource(uint8_t source_set_idx);
|
||||
void setPosVelYawSourceSet(uint8_t source_set_idx);
|
||||
|
||||
// write EKF information to on-board logs
|
||||
void Log_Write();
|
||||
|
Loading…
Reference in New Issue
Block a user