Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_Backend.h
Views: 1798
#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_body(Vector3f& dir_body) {31if (have_los_meas()) {32dir_body = _los_meas_body;33return true;34}35return false;36};3738// returns system time in milliseconds of last los measurement39uint32_t los_meas_time_ms() { return _los_meas_time_ms; };4041// return true if there is a valid los measurement available42bool have_los_meas() { return _have_los_meas; };4344// returns distance to target in meters (0 means distance is not known)45float distance_to_target() { return _distance_to_target; };4647// parses a mavlink message from the companion computer48virtual void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) {};4950// get bus parameter51int8_t get_bus(void) const { return _frontend._bus.get(); }5253protected:54const AC_PrecLand& _frontend; // reference to precision landing front end55AC_PrecLand::precland_state &_state; // reference to this instances state5657Vector3f _los_meas_body; // unit vector in body frame pointing towards target58uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured59bool _have_los_meas; // true if there is a valid measurement from the sensor60float _distance_to_target; // distance from the sensor to landing target in meters61};6263#endif // AC_PRECLAND_ENABLED646566