APM:Libraries
AP_Beacon_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_Math/AP_Math.h>
19 #include <AP_HAL/AP_HAL.h>
20 #include "AP_Beacon.h"
21 
23 {
24 public:
25  // constructor. This incorporates initialisation as well.
26  AP_Beacon_Backend(AP_Beacon &frontend);
27 
28  // return true if sensor is basically healthy (we are receiving data)
29  virtual bool healthy() = 0;
30 
31  // update
32  virtual void update() = 0;
33 
34  // set vehicle position, pos should be in the beacon's local frame
35  void set_vehicle_position(const Vector3f& pos, float accuracy_estimate);
36 
37  // set individual beacon distance in meters
38  void set_beacon_distance(uint8_t beacon_instance, float distance);
39 
40  // configure beacon's position in meters from origin
41  // pos should be in the beacon's local frame
42  void set_beacon_position(uint8_t beacon_instance, const Vector3f& pos);
43 
44  float get_beacon_origin_lat(void) const { return _frontend.origin_lat; }
45  float get_beacon_origin_lon(void) const { return _frontend.origin_lon; }
46  float get_beacon_origin_alt(void) const { return _frontend.origin_alt; }
47 
48 protected:
49 
50  // references
52 
53  // yaw correction
54  int16_t orient_yaw_deg; // cached version of orient_yaw parameter
55  float orient_cos_yaw = 0.0f;
56  float orient_sin_yaw = 1.0f;
57 
58  // yaw correction methods
60 };
void set_beacon_distance(uint8_t beacon_instance, float distance)
float get_beacon_origin_lat(void) const
virtual void update()=0
AP_Float origin_lat
Definition: AP_Beacon.h:117
float distance
Definition: location.cpp:94
AP_Float origin_alt
Definition: AP_Beacon.h:119
float get_beacon_origin_alt(void) const
Vector3f correct_for_orient_yaw(const Vector3f &vector)
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
float get_beacon_origin_lon(void) const
Common definitions and utility routines for the ArduPilot libraries.
AP_Float origin_lon
Definition: AP_Beacon.h:118
AP_Beacon_Backend(AP_Beacon &frontend)
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
virtual bool healthy()=0