Copter: style formatting

This commit is contained in:
Bill Geyer 2023-01-29 14:55:02 -05:00 committed by Bill Geyer
parent b24a6fe15f
commit 1c9b4a8ac3
1 changed files with 28 additions and 28 deletions

View File

@ -5,7 +5,7 @@
#if FRAME_CONFIG == HELI_FRAME
#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 250 // we are in "dynamic flight" when the speed is over 2.5m/s for 2 seconds
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 250 // we are in "dynamic flight" when the speed is over 2.5m/s for 2 seconds
#endif
// counter to control dynamic flight profile
@ -37,7 +37,7 @@ void Copter::check_dynamic_flight(void)
// get horizontal speed
const float speed = inertial_nav.get_speed_xy_cms();
moving = (speed >= HELI_DYNAMIC_FLIGHT_SPEED_MIN);
}else{
} else {
// with no GPS lock base it on throttle and forward lean angle
moving = (motors->get_throttle() > 0.8f || ahrs.pitch_sensor < -1500);
}
@ -47,7 +47,7 @@ void Copter::check_dynamic_flight(void)
// rangefinder lock consider it to be dynamic flight
moving = (rangefinder.distance_cm_orient(ROTATION_PITCH_270) > 200);
}
if (moving) {
// if moving for 2 seconds, set the dynamic flight flag
if (!heli_flags.dynamic_flight) {
@ -57,12 +57,12 @@ void Copter::check_dynamic_flight(void)
heli_dynamic_flight_counter = 100;
}
}
}else{
} else {
// if not moving for 2 seconds, clear the dynamic flight flag
if (heli_flags.dynamic_flight) {
if (heli_dynamic_flight_counter > 0) {
heli_dynamic_flight_counter--;
}else{
} else {
heli_flags.dynamic_flight = false;
}
}
@ -88,9 +88,9 @@ void Copter::update_heli_control_dynamics(void)
motors->set_land_complete(false);
}
if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))){
if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))) {
// if we are landed or there is no rotor power demanded, decrement slew scalar
hover_roll_trim_scalar_slew--;
hover_roll_trim_scalar_slew--;
} else {
// if we are not landed and motor power is demanded, increment slew scalar
hover_roll_trim_scalar_slew++;
@ -161,31 +161,31 @@ void Copter::heli_update_rotor_speed_targets()
uint8_t rsc_control_mode = motors->get_rsc_mode();
switch (rsc_control_mode) {
case ROTOR_CONTROL_MODE_PASSTHROUGH:
// pass through pilot desired rotor speed from the RC
if (get_pilot_desired_rotor_speed() > 0.01) {
ap.motor_interlock_switch = true;
motors->set_desired_rotor_speed(get_pilot_desired_rotor_speed());
} else {
ap.motor_interlock_switch = false;
motors->set_desired_rotor_speed(0.0f);
}
break;
case ROTOR_CONTROL_MODE_SETPOINT:
case ROTOR_CONTROL_MODE_THROTTLECURVE:
case ROTOR_CONTROL_MODE_AUTOTHROTTLE:
if (motors->get_interlock()) {
motors->set_desired_rotor_speed(motors->get_rsc_setpoint());
}else{
motors->set_desired_rotor_speed(0.0f);
}
break;
case ROTOR_CONTROL_MODE_PASSTHROUGH:
// pass through pilot desired rotor speed from the RC
if (get_pilot_desired_rotor_speed() > 0.01) {
ap.motor_interlock_switch = true;
motors->set_desired_rotor_speed(get_pilot_desired_rotor_speed());
} else {
ap.motor_interlock_switch = false;
motors->set_desired_rotor_speed(0.0f);
}
break;
case ROTOR_CONTROL_MODE_SETPOINT:
case ROTOR_CONTROL_MODE_THROTTLECURVE:
case ROTOR_CONTROL_MODE_AUTOTHROTTLE:
if (motors->get_interlock()) {
motors->set_desired_rotor_speed(motors->get_rsc_setpoint());
} else {
motors->set_desired_rotor_speed(0.0f);
}
break;
}
// when rotor_runup_complete changes to true, log event
if (!rotor_runup_complete_last && motors->rotor_runup_complete()){
if (!rotor_runup_complete_last && motors->rotor_runup_complete()) {
AP::logger().Write_Event(LogEvent::ROTOR_RUNUP_COMPLETE);
} else if (rotor_runup_complete_last && !motors->rotor_runup_complete() && !heli_flags.in_autorotation){
} else if (rotor_runup_complete_last && !motors->rotor_runup_complete() && !heli_flags.in_autorotation) {
AP::logger().Write_Event(LogEvent::ROTOR_SPEED_BELOW_CRITICAL);
}
rotor_runup_complete_last = motors->rotor_runup_complete();