APM:Libraries
AP_Beacon_Backend.cpp
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 
16 #include "AP_Beacon_Backend.h"
17 // debug
18 #include <stdio.h>
19 
20 /*
21  base class constructor.
22  This incorporates initialisation as well.
23 */
25  _frontend(frontend)
26 {
27 }
28 
29 // set vehicle position:
30 // pos should be in the beacon's local frame in meters
31 // accuracy_estimate is also in meters
32 void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy_estimate)
33 {
35  _frontend.veh_pos_accuracy = accuracy_estimate;
37 }
38 
39 // set individual beacon distance in meters
40 void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
41 {
42  // sanity check instance
43  if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
44  return;
45  }
46 
47  // setup new beacon
48  if (beacon_instance >= _frontend.num_beacons) {
49  _frontend.num_beacons = beacon_instance+1;
50  }
51 
53  _frontend.beacon_state[beacon_instance].distance = distance;
54  _frontend.beacon_state[beacon_instance].healthy = true;
55 }
56 
57 // configure beacon's position in meters from origin
58 // pos should be in the beacon's local frame (meters)
59 void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
60 {
61  // sanity check instance
62  if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
63  return;
64  }
65 
66  // setup new beacon
67  if (beacon_instance >= _frontend.num_beacons) {
68  _frontend.num_beacons = beacon_instance+1;
69  }
70 
71  // set position after correcting yaw
72  _frontend.beacon_state[beacon_instance].position = correct_for_orient_yaw(pos);
73 }
74 
75 // rotate vector (meters) to correct for beacon system yaw orientation
77 {
78  // exit immediately if no correction
79  if (_frontend.orient_yaw == 0) {
80  return vector;
81  }
82 
83  // check for change in parameter value and update constants
86 
87  // calculate rotation constants
89  orient_cos_yaw = cosf(radians(orient_yaw_deg));
90  orient_sin_yaw = sinf(radians(orient_yaw_deg));
91  }
92 
93  // rotate x,y by -orient_yaw
94  Vector3f vec_rotated;
95  vec_rotated.x = vector.x*orient_cos_yaw - vector.y*orient_sin_yaw;
96  vec_rotated.y = vector.x*orient_sin_yaw + vector.y*orient_cos_yaw;
97  vec_rotated.z = vector.z;
98  return vec_rotated;
99 }
float veh_pos_accuracy
Definition: AP_Beacon.h:128
void set_beacon_distance(uint8_t beacon_instance, float distance)
#define AP_BEACON_MAX_BEACONS
Definition: AP_Beacon.h:25
AP_Int16 orient_yaw
Definition: AP_Beacon.h:120
float distance
Definition: location.cpp:94
uint32_t distance_update_ms
Definition: AP_Beacon.h:49
Vector3f correct_for_orient_yaw(const Vector3f &vector)
float wrap_180(const T angle, float unit_mod)
Definition: AP_Math.cpp:96
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
uint8_t num_beacons
Definition: AP_Beacon.h:132
T z
Definition: vector3.h:67
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
uint32_t veh_pos_update_ms
Definition: AP_Beacon.h:129
static constexpr float radians(float deg)
Definition: AP_Math.h:158
Vector3f veh_pos_ned
Definition: AP_Beacon.h:127
BeaconState beacon_state[AP_BEACON_MAX_BEACONS]
Definition: AP_Beacon.h:133
AP_Beacon_Backend(AP_Beacon &frontend)
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
T x
Definition: vector3.h:67