mirror of https://github.com/ArduPilot/ardupilot
Tools: implement EK3GPSDisable in replay
This commit is contained in:
parent
f46d0750cc
commit
346712fe5d
|
@ -73,6 +73,9 @@ void LR_MsgHandler_REV2::process_message(uint8_t *msgbytes)
|
||||||
break;
|
break;
|
||||||
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
||||||
break;
|
break;
|
||||||
|
case AP_DAL::Event::EK3GPSDisable:
|
||||||
|
case AP_DAL::Event::EK3GPSEnable:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
if (replay_force_ekf3) {
|
if (replay_force_ekf3) {
|
||||||
LR_MsgHandler_REV3 h{f, ekf2, ekf3};
|
LR_MsgHandler_REV3 h{f, ekf2, ekf3};
|
||||||
|
@ -133,6 +136,12 @@ void LR_MsgHandler_REV3::process_message(uint8_t *msgbytes)
|
||||||
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2:
|
||||||
ekf3.setPosVelYawSourceSet(uint8_t(msg.event)-uint8_t(AP_DAL::Event::setSourceSet0));
|
ekf3.setPosVelYawSourceSet(uint8_t(msg.event)-uint8_t(AP_DAL::Event::setSourceSet0));
|
||||||
break;
|
break;
|
||||||
|
case AP_DAL::Event::EK3GPSDisable:
|
||||||
|
ekf3.force_gps_disable(true);
|
||||||
|
break;
|
||||||
|
case AP_DAL::Event::EK3GPSEnable:
|
||||||
|
ekf3.force_gps_disable(false);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (replay_force_ekf2) {
|
if (replay_force_ekf2) {
|
||||||
|
|
Loading…
Reference in New Issue