mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Replay: support set source events
This commit is contained in:
parent
a91894ff2d
commit
d823ed6358
@ -71,6 +71,8 @@ void LR_MsgHandler_REV2::process_message(uint8_t *msgbytes)
|
||||
case AP_DAL::Event::checkLaneSwitch:
|
||||
ekf2.checkLaneSwitch();
|
||||
break;
|
||||
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
||||
break;
|
||||
}
|
||||
if (replay_force_ekf3) {
|
||||
LR_MsgHandler_REV3 h{f, ekf2, ekf3};
|
||||
@ -128,6 +130,9 @@ void LR_MsgHandler_REV3::process_message(uint8_t *msgbytes)
|
||||
case AP_DAL::Event::checkLaneSwitch:
|
||||
ekf3.checkLaneSwitch();
|
||||
break;
|
||||
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
||||
ekf3.setPosVelYawSourceSet(uint8_t(msg.event)-uint8_t(AP_DAL::Event::setSourceSet0));
|
||||
break;
|
||||
}
|
||||
|
||||
if (replay_force_ekf2) {
|
||||
|
Loading…
Reference in New Issue
Block a user