Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_Backend.h
9742 views
#pragma once12#include "AC_PrecLand_config.h"34#if AC_PRECLAND_ENABLED56#include "AC_PrecLand.h"7#include <AP_Math/AP_Math.h>8#include <AC_PID/AC_PID.h>91011class AC_PrecLand_Backend12{13public:14// Constructor15AC_PrecLand_Backend(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state) :16_frontend(frontend),17_state(state) {}1819// destructor20virtual ~AC_PrecLand_Backend() {}2122// perform any required initialisation of backend23virtual void init() = 0;2425// retrieve updates from sensor26virtual void update() = 0;2728// provides a unit vector towards the target in body frame29// returns same as have_los_meas()30bool get_los_meas(Vector3f& vec_unit, AC_PrecLand::VectorFrame& frame) const {31if (!_los_meas.valid) {32return false;33}34vec_unit = _los_meas.vec_unit;35frame = _los_meas.frame;36return true;37};3839// returns system time in milliseconds of last los measurement40uint32_t los_meas_time_ms() const { return _los_meas.time_ms; };4142// returns distance to target in meters (0 means distance is not known)43float distance_to_target() const { return _distance_to_target; };4445// parses a mavlink message from the companion computer46virtual void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) {};4748// get bus parameter49int8_t get_bus(void) const { return _frontend._bus.get(); }5051protected:52const AC_PrecLand& _frontend; // reference to precision landing front end53AC_PrecLand::precland_state &_state; // reference to this instances state5455struct {56Vector3f vec_unit; // unit vector pointing towards target in earth or body frame (see frame)57AC_PrecLand::VectorFrame frame; // frame of vector pointing towards target58uint32_t time_ms; // system time in milliseconds when the vector was measured59bool valid; // true if there is a valid measurement from the sensor60} _los_meas;61float _distance_to_target; // distance from the sensor to landing target in meters62};6364#endif // AC_PRECLAND_ENABLED656667