SITL: Simplify boolean expression

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-05 13:22:06 -03:00 committed by Andrew Tridgell
parent ba2adac869
commit 300a14aaae
2 changed files with 2 additions and 6 deletions

View File

@ -64,11 +64,7 @@ void Helicopter::update(const struct sitl_input &input)
// get wind vector setup
update_wind(input);
if (input.servos[7] > 1400) {
motor_interlock = true;
} else {
motor_interlock = false;
}
motor_interlock = input.servos[7] > 1400;
float rsc = constrain_float((input.servos[7]-1000) / 1000.0f, 0, 1);
float rsc_scale = rsc/rsc_setpoint;

View File

@ -60,7 +60,7 @@ float SerialProximitySensor::measure_distance_at_angle_bf(const Location &locati
count++;
// the 1000 here is so the files don't grow unbounded
const bool write_debug_files = true && count < 1000;
const bool write_debug_files = count < 1000;
FILE *rayfile = nullptr;
if (write_debug_files) {