mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF3: log set source events
This commit is contained in:
parent
8939974333
commit
83d78b6336
@ -1083,6 +1083,9 @@ void NavEKF3::resetCoreErrors(void)
|
|||||||
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
|
||||||
void NavEKF3::setPosVelYawSourceSet(uint8_t source_set_idx)
|
void NavEKF3::setPosVelYawSourceSet(uint8_t source_set_idx)
|
||||||
{
|
{
|
||||||
|
if (source_set_idx < AP_NAKEKF_SOURCE_SET_MAX) {
|
||||||
|
AP::dal().log_event3(AP_DAL::Event(uint8_t(AP_DAL::Event::setSourceSet0)+source_set_idx));
|
||||||
|
}
|
||||||
sources.setPosVelYawSourceSet(source_set_idx);
|
sources.setPosVelYawSourceSet(source_set_idx);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user