2019-08-15 05:23:36 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#include "AP_Proximity_config.h"
|
2021-03-25 04:32:09 -03:00
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#if AP_PROXIMITY_AIRSIMSITL_ENABLED
|
2019-07-10 19:15:58 -03:00
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#include "AP_Proximity_AirSimSITL.h"
|
2019-07-10 19:15:58 -03:00
|
|
|
|
|
|
|
#define PROXIMITY_MAX_RANGE 100.0f
|
2021-01-10 14:14:24 -04:00
|
|
|
#define PROXIMITY_ACCURACY 0.1f // minimum distance (in meters) between objects sent to object database
|
2019-07-10 19:15:58 -03:00
|
|
|
|
|
|
|
// update the state of the sensor
|
|
|
|
void AP_Proximity_AirSimSITL::update(void)
|
|
|
|
{
|
|
|
|
SITL::vector3f_array &points = sitl->state.scanner.points;
|
|
|
|
if (points.length == 0) {
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::NoData);
|
2019-07-10 19:15:58 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-09-27 05:58:52 -03:00
|
|
|
set_status(AP_Proximity::Status::Good);
|
2020-12-14 03:45:26 -04:00
|
|
|
|
|
|
|
// reset all faces to default so that it can be filled with the fresh lidar data
|
2022-07-07 00:35:43 -03:00
|
|
|
frontend.boundary.reset();
|
2020-12-14 03:45:26 -04:00
|
|
|
|
|
|
|
// precalculate sq of min distance
|
|
|
|
const float distance_min_sq = sq(distance_min());
|
|
|
|
|
|
|
|
// variables used to reduce data sent to object database
|
|
|
|
const float accuracy_sq = sq(PROXIMITY_ACCURACY);
|
|
|
|
bool prev_pos_valid = false;
|
|
|
|
Vector2f prev_pos;
|
2021-03-08 13:21:45 -04:00
|
|
|
// clear temp boundary since we have a new message
|
|
|
|
temp_boundary.reset();
|
2019-07-10 19:15:58 -03:00
|
|
|
|
|
|
|
for (uint16_t i=0; i<points.length; i++) {
|
|
|
|
Vector3f &point = points.data[i];
|
|
|
|
if (point.is_zero()) {
|
|
|
|
continue;
|
|
|
|
}
|
2019-12-13 11:29:30 -04:00
|
|
|
|
2020-12-14 03:45:26 -04:00
|
|
|
// calculate distance to point and check larger than min distance
|
2021-01-10 14:14:24 -04:00
|
|
|
const Vector2f new_pos = Vector2f{point.x, point.y};
|
2020-12-14 03:45:26 -04:00
|
|
|
const float distance_sq = new_pos.length_squared();
|
|
|
|
if (distance_sq > distance_min_sq) {
|
|
|
|
|
|
|
|
// add distance to the 3D boundary
|
|
|
|
const float yaw_angle_deg = wrap_360(degrees(atan2f(point.y, point.x)));
|
2022-07-07 00:35:43 -03:00
|
|
|
const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(yaw_angle_deg);
|
2021-03-08 13:21:45 -04:00
|
|
|
// store the min distance in each face in a temp boundary
|
|
|
|
temp_boundary.add_distance(face, yaw_angle_deg, safe_sqrt(distance_sq));
|
2020-12-14 03:45:26 -04:00
|
|
|
|
|
|
|
// check distance from previous point to reduce amount of data sent to object database
|
|
|
|
if (!prev_pos_valid || ((new_pos - prev_pos).length_squared() >= accuracy_sq)) {
|
|
|
|
// update OA database
|
|
|
|
database_push(yaw_angle_deg, safe_sqrt(distance_sq));
|
|
|
|
// store point
|
|
|
|
prev_pos_valid = true;
|
|
|
|
prev_pos = new_pos;
|
2019-12-13 11:29:30 -04:00
|
|
|
}
|
2019-07-10 19:15:58 -03:00
|
|
|
}
|
|
|
|
}
|
2021-03-08 13:21:45 -04:00
|
|
|
// copy temp boundary to real boundary
|
2022-07-07 00:35:43 -03:00
|
|
|
temp_boundary.update_3D_boundary(state.instance, frontend.boundary);
|
2019-07-10 19:15:58 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// get maximum and minimum distances (in meters) of primary sensor
|
|
|
|
float AP_Proximity_AirSimSITL::distance_max() const
|
|
|
|
{
|
|
|
|
return PROXIMITY_MAX_RANGE;
|
|
|
|
}
|
|
|
|
|
|
|
|
float AP_Proximity_AirSimSITL::distance_min() const
|
|
|
|
{
|
|
|
|
return 0.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get distance upwards in meters. returns true on success
|
|
|
|
bool AP_Proximity_AirSimSITL::get_upward_distance(float &distance) const
|
|
|
|
{
|
|
|
|
// we don't have an upward facing laser
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-04-05 09:25:54 -03:00
|
|
|
#endif // AP_PROXIMITY_AIRSIMSITL_ENABLED
|