20 virtual void init() = 0;
AC_PrecLand_Backend(const AC_PrecLand &frontend, AC_PrecLand::precland_state &state)
Generic PID algorithm, with EEPROM-backed storage of constants.
virtual bool have_los_meas()=0
virtual void handle_msg(mavlink_message_t *msg)
const AC_PrecLand & _frontend
virtual ~AC_PrecLand_Backend()
virtual float distance_to_target()
virtual uint32_t los_meas_time_ms()=0
virtual bool get_los_body(Vector3f &dir_body)=0
int8_t get_bus(void) const
AC_PrecLand::precland_state & _state
Common definitions and utility routines for the ArduPilot libraries.