Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: remove dead stores from rangefinder_range #29173

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 19 additions & 19 deletions libraries/SITL/SIM_Aircraft.cpp
Original file line number Diff line number Diff line change
@@ -536,6 +536,25 @@ float Aircraft::perpendicular_distance_to_rangefinder_surface() const

float Aircraft::rangefinder_range() const
{
float altitude = perpendicular_distance_to_rangefinder_surface();

// sensor position offset in body frame
const Vector3f relPosSensorBF = sitl->rngfnd_pos_offset;

// n.b. the following code is assuming rotation-pitch-270:
// adjust altitude for position of the sensor on the vehicle if position offset is non-zero
if (!relPosSensorBF.is_zero()) {
// get a rotation matrix following DCM conventions (body to earth)
Matrix3f rotmat;
sitl->state.quaternion.rotation_matrix(rotmat);
// rotate the offset into earth frame
const Vector3f relPosSensorEF = rotmat * relPosSensorBF;
// correct the altitude at the sensor
altitude -= relPosSensorEF.z;
}

const auto orientation = (Rotation)sitl->sonar_rot.get();
#if SITL_RANGEFINDER_AS_OBJECT_SENSOR

float roll = sitl->state.rollDeg;
float pitch = sitl->state.pitchDeg;
@@ -563,25 +582,6 @@ float Aircraft::rangefinder_range() const
}
}

float altitude = perpendicular_distance_to_rangefinder_surface();

// sensor position offset in body frame
const Vector3f relPosSensorBF = sitl->rngfnd_pos_offset;

// n.b. the following code is assuming rotation-pitch-270:
// adjust altitude for position of the sensor on the vehicle if position offset is non-zero
if (!relPosSensorBF.is_zero()) {
// get a rotation matrix following DCM conventions (body to earth)
Matrix3f rotmat;
sitl->state.quaternion.rotation_matrix(rotmat);
// rotate the offset into earth frame
const Vector3f relPosSensorEF = rotmat * relPosSensorBF;
// correct the altitude at the sensor
altitude -= relPosSensorEF.z;
}

const auto orientation = (Rotation)sitl->sonar_rot.get();
#if SITL_RANGEFINDER_AS_OBJECT_SENSOR
/*
rover and copter using SITL rangefinders as obstacle sensors
*/

Unchanged files with check annotations Beta

# double-notch should do better, but check for within 5%
if peakdb2 * 1.05 > peakdb1:
raise NotAchievedException(

Check failure on line 6170 in Tools/autotest/arducopter.py

GitHub Actions / autotest (sitltest-copter-tests2b)

vehicle_test_suite.NotAchievedException: Double-notch peak was higher than single-notch peak -26.256809dB > -27.979935dB
"Double-notch peak was higher than single-notch peak %fdB > %fdB" %
(peakdb2, peakdb1))
self.context_pop()
if ex is not None:
raise ex

Check failure on line 6194 in Tools/autotest/arducopter.py

GitHub Actions / autotest (sitltest-copter-tests2b)

File "/__w/ardupilot/ardupilot/Tools/autotest/arducopter.py", line 6170, in DynamicNotches
def DynamicRpmNotches(self):
"""Use dynamic harmonic notch to control motor noise via ESC telemetry."""