mirror of https://github.com/ArduPilot/ardupilot
Tools: removed inhibitGps and inhibitGpsVertVel options
these were unused
This commit is contained in:
parent
80f7906744
commit
4e4a044d5d
|
@ -59,9 +59,6 @@ void LR_MsgHandler_REV2::process_message(uint8_t *msgbytes)
|
|||
case AP_DAL::Event::resetHeightDatum:
|
||||
ekf2.resetHeightDatum();
|
||||
break;
|
||||
case AP_DAL::Event::setInhibitGPS:
|
||||
ekf2.setInhibitGPS();
|
||||
break;
|
||||
case AP_DAL::Event::setTakeoffExpected:
|
||||
ekf2.setTakeoffExpected(true);
|
||||
break;
|
||||
|
@ -74,12 +71,6 @@ void LR_MsgHandler_REV2::process_message(uint8_t *msgbytes)
|
|||
case AP_DAL::Event::unsetTouchdownExpected:
|
||||
ekf2.setTouchdownExpected(false);
|
||||
break;
|
||||
case AP_DAL::Event::setInhibitGpsVertVelUse:
|
||||
ekf2.setInhibitGpsVertVelUse(true);
|
||||
break;
|
||||
case AP_DAL::Event::unsetInhibitGpsVertVelUse:
|
||||
ekf2.setInhibitGpsVertVelUse(false);
|
||||
break;
|
||||
case AP_DAL::Event::setTerrainHgtStable:
|
||||
ekf2.setTerrainHgtStable(true);
|
||||
break;
|
||||
|
@ -137,9 +128,6 @@ void LR_MsgHandler_REV3::process_message(uint8_t *msgbytes)
|
|||
case AP_DAL::Event::resetHeightDatum:
|
||||
ekf3.resetHeightDatum();
|
||||
break;
|
||||
case AP_DAL::Event::setInhibitGPS:
|
||||
ekf3.setInhibitGPS();
|
||||
break;
|
||||
case AP_DAL::Event::setTakeoffExpected:
|
||||
ekf3.setTakeoffExpected(true);
|
||||
break;
|
||||
|
@ -152,12 +140,6 @@ void LR_MsgHandler_REV3::process_message(uint8_t *msgbytes)
|
|||
case AP_DAL::Event::unsetTouchdownExpected:
|
||||
ekf3.setTouchdownExpected(false);
|
||||
break;
|
||||
case AP_DAL::Event::setInhibitGpsVertVelUse:
|
||||
ekf3.setInhibitGpsVertVelUse(true);
|
||||
break;
|
||||
case AP_DAL::Event::unsetInhibitGpsVertVelUse:
|
||||
ekf3.setInhibitGpsVertVelUse(false);
|
||||
break;
|
||||
case AP_DAL::Event::setTerrainHgtStable:
|
||||
ekf3.setTerrainHgtStable(true);
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue