Skip to content

Commit

Permalink
SITL: support more rangefinder orientations
Browse files Browse the repository at this point in the history
allows for quadplane tailsitter rangefinders
  • Loading branch information
tridge committed Sep 11, 2024
1 parent 53a4b5a commit 7a43d15
Showing 1 changed file with 24 additions and 10 deletions.
34 changes: 24 additions & 10 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include <AP_Filesystem/AP_Filesystem.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL_SITL/HAL_SITL_Class.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>

using namespace SITL;

Expand Down Expand Up @@ -505,12 +506,21 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
float Aircraft::perpendicular_distance_to_rangefinder_surface() const
{
switch ((Rotation)sitl->sonar_rot.get()) {
case Rotation::ROTATION_PITCH_270:
return sitl->state.height_agl;
#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane)
/*
for copter and rover we treat these yaw rotations as meaning
the sensor is being used for object avoidance. This is a
hack and should be removed in the future. For plane we
can't do this as it would break the use of a YAW_180 sensor
for tailsitter landings
*/
case ROTATION_NONE ... ROTATION_YAW_315:
// assume these are avoidance sensors
return sitl->measure_distance_at_angle_bf(location, sitl->sonar_rot.get()*45);
#endif
default:
AP_BoardConfig::config_error("Bad simulated sonar rotation");
// assume all others are ground sensing rangefinders
return sitl->state.height_agl;
}
}

Expand Down Expand Up @@ -543,11 +553,6 @@ float Aircraft::rangefinder_range() const
}
}

if (fabs(roll) >= 90.0 || fabs(pitch) >= 90.0) {
// not going to hit the ground....
return INFINITY;
}

float altitude = perpendicular_distance_to_rangefinder_surface();

// sensor position offset in body frame
Expand All @@ -565,8 +570,17 @@ float Aircraft::rangefinder_range() const
altitude -= relPosSensorEF.z;
}

// adjust for apparent altitude with roll
altitude /= cosf(radians(roll)) * cosf(radians(pitch));
// adjust for rotation based on orientation of the sensor
Matrix3f rotmat;
sitl->state.quaternion.rotation_matrix(rotmat);
Vector3f v{1, 0, 0};
v.rotate((Rotation)sitl->sonar_rot.get());
v = rotmat * v;

if (!is_positive(v.z)) {
return INFINITY;
}
altitude /= v.z;

// Add some noise on reading
altitude += sitl->sonar_noise * rand_float();
Expand Down

0 comments on commit 7a43d15

Please sign in to comment.