mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
SITL: Simplify boolean expression
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
ba2adac869
commit
300a14aaae
@ -64,11 +64,7 @@ void Helicopter::update(const struct sitl_input &input)
|
|||||||
// get wind vector setup
|
// get wind vector setup
|
||||||
update_wind(input);
|
update_wind(input);
|
||||||
|
|
||||||
if (input.servos[7] > 1400) {
|
motor_interlock = input.servos[7] > 1400;
|
||||||
motor_interlock = true;
|
|
||||||
} else {
|
|
||||||
motor_interlock = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
float rsc = constrain_float((input.servos[7]-1000) / 1000.0f, 0, 1);
|
float rsc = constrain_float((input.servos[7]-1000) / 1000.0f, 0, 1);
|
||||||
float rsc_scale = rsc/rsc_setpoint;
|
float rsc_scale = rsc/rsc_setpoint;
|
||||||
|
@ -60,7 +60,7 @@ float SerialProximitySensor::measure_distance_at_angle_bf(const Location &locati
|
|||||||
count++;
|
count++;
|
||||||
|
|
||||||
// the 1000 here is so the files don't grow unbounded
|
// 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;
|
FILE *rayfile = nullptr;
|
||||||
if (write_debug_files) {
|
if (write_debug_files) {
|
||||||
|
Loading…
Reference in New Issue
Block a user