APM:Libraries
AP_Proximity_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 
17 #include <AP_HAL/AP_HAL.h>
18 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
19 #include <AP_Param/AP_Param.h>
20 #include "AP_Proximity_SITL.h"
21 #include <stdio.h>
22 
23 extern const AP_HAL::HAL& hal;
24 
25 #define PROXIMITY_MAX_RANGE 200.0f
26 #define PROXIMITY_ACCURACY 0.1f
27 
28 /*
29  The constructor also initialises the proximity sensor.
30 */
33  AP_Proximity_Backend(_frontend, _state)
34 {
36  ap_var_type ptype;
37  fence_count = (AP_Int8 *)AP_Param::find("FENCE_TOTAL", &ptype);
38  if (fence_count == nullptr || ptype != AP_PARAM_INT8) {
39  AP_HAL::panic("Proximity_SITL: Failed to find FENCE_TOTAL");
40  }
41  fence_alt_max = (AP_Float *)AP_Param::find("FENCE_ALT_MAX", &ptype);
42  if (fence_alt_max == nullptr || ptype != AP_PARAM_FLOAT) {
43  AP_HAL::panic("Proximity_SITL: Failed to find FENCE_ALT_MAX");
44  }
45 }
46 
47 // update the state of the sensor
49 {
50  load_fence();
51  current_loc.lat = sitl->state.latitude * 1.0e7;
52  current_loc.lng = sitl->state.longitude * 1.0e7;
53  current_loc.alt = sitl->state.altitude * 1.0e2;
54  if (fence && fence_loader.boundary_valid(fence_count->get(), fence, true)) {
55  // update distance in one sector
60  update_boundary_for_sector(last_sector);
61  } else {
63  }
64  last_sector++;
65  if (last_sector >= _num_sectors) {
66  last_sector = 0;
67  }
68  } else {
70  }
71 }
72 
74 {
75  uint32_t now = AP_HAL::millis();
76  if (now - last_load_ms < 1000) {
77  return;
78  }
79  last_load_ms = now;
80 
81  if (fence == nullptr) {
83  }
84  if (fence == nullptr) {
85  return;
86  }
87  for (uint8_t i=0; i<fence_count->get(); i++) {
89  }
90 }
91 
92 // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
93 bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) const
94 {
95  if (!fence_loader.boundary_valid(fence_count->get(), fence, true)) {
96  return false;
97  }
98 
99  // convert to earth frame
100  angle_deg = wrap_360(sitl->state.yawDeg + angle_deg);
101 
102  /*
103  simple bisection search to find distance. Not really efficient,
104  but we can afford the CPU in SITL
105  */
106  float min_dist = 0, max_dist = PROXIMITY_MAX_RANGE;
107  while (max_dist - min_dist > PROXIMITY_ACCURACY) {
108  float test_dist = (max_dist+min_dist)*0.5f;
109  Location loc = current_loc;
110  location_update(loc, angle_deg, test_dist);
111  Vector2l vecloc(loc.lat, loc.lng);
112  if (fence_loader.boundary_breached(vecloc, fence_count->get(), fence, true)) {
113  max_dist = test_dist;
114  } else {
115  min_dist = test_dist;
116  }
117  }
118  distance = min_dist;
119  return true;
120 }
121 
122 // get maximum and minimum distances (in meters) of primary sensor
124 {
125  return PROXIMITY_MAX_RANGE;
126 }
128 {
129  return 0.0f;
130 }
131 
132 // get distance upwards in meters. returns true on success
134 {
135  // return distance to fence altitude
136  distance = MAX(0.0f, fence_alt_max->get() - sitl->height_agl);
137  return true;
138 }
139 
140 #endif // CONFIG_HAL_BOARD
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
bool get_distance_to_fence(float angle_deg, float &distance) const
bool _distance_valid[PROXIMITY_SECTORS_MAX]
float distance_max() const
bool get_upward_distance(float &distance) const
ap_var_type
Definition: AP_Param.h:124
float _angle[PROXIMITY_SECTORS_MAX]
float height_agl
Definition: SITL.h:80
double longitude
Definition: SITL.h:14
static AP_Param * find(const char *name, enum ap_var_type *ptype)
Definition: AP_Param.cpp:821
uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX]
bool load_point_from_eeprom(uint16_t i, Vector2l &point)
void set_status(AP_Proximity::Proximity_Status status)
float distance
Definition: location.cpp:94
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool boundary_valid(uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
float distance_min() const
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
A system for managing and storing variables that are of general interest to the system.
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
float _distance[PROXIMITY_SECTORS_MAX]
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
#define PROXIMITY_MAX_RANGE
AP_Float * fence_alt_max
#define f(i)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
double yawDeg
Definition: SITL.h:20
uint32_t millis()
Definition: system.cpp:157
AC_PolyFence_loader fence_loader
AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
#define PROXIMITY_ACCURACY
void update_boundary_for_sector(uint8_t sector)
double latitude
Definition: SITL.h:14
void * create_point_array(uint8_t element_size)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
bool boundary_breached(const Vector2< T > &location, uint16_t num_points, const Vector2< T > *points, bool contains_return_point) const
double altitude
Definition: SITL.h:15
struct sitl_fdm state
Definition: SITL.h:71
void update(void) override