APM:Libraries
AP_Beacon_SITL.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_HAL/AP_HAL.h>
17 
18 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
19 
20 #include "AP_Beacon_SITL.h"
21 #include <stdio.h>
22 
23 extern const AP_HAL::HAL& hal;
24 
25 #define NUM_BEACONS 4
26 /*
27  * Define a rectangular pattern of beacons with the pattern centroid located at the beacon origin as defined by the following params:
28  *
29  * BCN_ALT - Height above the WGS-84 geoid (m)
30  * BCN_LATITUDE - WGS-84 latitude (deg)
31  * BCN_LONGITUDE - WGS-84 longitude (deg)
32  *
33  * The spacing between beacons in the North/South and East/West directions is defined by the following parameters:
34  */
35 #define BEACON_SPACING_NORTH 10.0
36 #define BEACON_SPACING_EAST 20.0
37 
38 // The centroid of the pattern can be moved using using the following parameters:
39 #define ORIGIN_OFFSET_NORTH 2.5 // shifts beacon pattern centroid North (m)
40 #define ORIGIN_OFFSET_EAST 5.0 // shifts beacon pattern centroid East (m)
41 
42 // constructor
44  AP_Beacon_Backend(frontend)
45 {
47 }
48 
49 // return true if sensor is basically healthy (we are receiving data)
51 {
52  // healthy if we have parsed a message within the past 300ms
54 }
55 
56 // update the state of the sensor
58 {
59  uint32_t now = AP_HAL::millis();
60  if (now - last_update_ms < 10) {
61  return;
62  }
63 
64  uint8_t beacon_id = next_beacon;
66 
67  // truth location of the flight vehicle
68  Location current_loc;
69  current_loc.lat = sitl->state.latitude * 1.0e7;
70  current_loc.lng = sitl->state.longitude * 1.0e7;
71  current_loc.alt = sitl->state.altitude * 1.0e2;
72 
73  // where the beacon system origin is located
74  Location beacon_origin;
75  beacon_origin.lat = get_beacon_origin_lat() * 1.0e7;
76  beacon_origin.lng = get_beacon_origin_lon() * 1.0e7;
77  beacon_origin.alt = get_beacon_origin_alt() * 1.0e2;
78 
79  // position of each beacon
80  Location beacon_loc = beacon_origin;
81  switch (beacon_id) {
82  case 0:
83  // NE corner
85  break;
86  case 1:
87  // SE corner
89  break;
90  case 2:
91  // SW corner
93  break;
94  case 3:
95  // NW corner
97  break;
98  }
99 
100  Vector2f beac_diff = location_diff(beacon_origin, beacon_loc);
101  Vector2f veh_diff = location_diff(beacon_origin, current_loc);
102 
103  Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (current_loc.alt - beacon_origin.alt)*1.0e-2);
104  Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_origin.alt - beacon_loc.alt)*1.0e-2);
105  Vector3f beac_veh_offset = veh_pos3d - beac_pos3d;
106 
107  set_beacon_position(beacon_id, beac_pos3d);
108  set_beacon_distance(beacon_id, beac_veh_offset.length());
109  set_vehicle_position(veh_pos3d, 0.5f);
110  last_update_ms = now;
111 
112 }
113 
114 #endif // CONFIG_HAL_BOARD
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
#define ORIGIN_OFFSET_NORTH
uint8_t next_beacon
void set_beacon_distance(uint8_t beacon_instance, float distance)
float get_beacon_origin_lat(void) const
double longitude
Definition: SITL.h:14
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
#define BEACON_SPACING_NORTH
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
T y
Definition: vector2.h:37
float get_beacon_origin_alt(void) const
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define f(i)
bool healthy() override
uint32_t last_update_ms
uint32_t millis()
Definition: system.cpp:157
#define AP_BEACON_TIMEOUT_MS
Definition: AP_Beacon.h:26
#define NUM_BEACONS
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
float get_beacon_origin_lon(void) const
float length(void) const
Definition: vector3.cpp:288
AP_Beacon_SITL(AP_Beacon &frontend)
T x
Definition: vector2.h:37
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
#define ORIGIN_OFFSET_EAST
#define BEACON_SPACING_EAST
void update() override
double latitude
Definition: SITL.h:14
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
double altitude
Definition: SITL.h:15
SITL::SITL * sitl
struct sitl_fdm state
Definition: SITL.h:71