forked from Archive/PX4-Autopilot
addressed review comments (fixes in error message and comments)
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
63a53d48e7
commit
bf311ed77d
|
@ -242,7 +242,7 @@ float FixedwingAttitudeControl::get_airspeed_and_update_scaling()
|
|||
} else {
|
||||
// VTOL: if we have no airspeed available and we are in hover mode then assume the lowest airspeed possible
|
||||
// this assumption is good as long as the vehicle is not hovering in a headwind which is much larger
|
||||
// than the minimum airspeed
|
||||
// than the stall airspeed
|
||||
if (_vehicle_status.is_vtol && _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
|
||||
&& !_vehicle_status.in_transition_mode) {
|
||||
airspeed = _param_fw_airspd_stall.get();
|
||||
|
@ -250,7 +250,7 @@ float FixedwingAttitudeControl::get_airspeed_and_update_scaling()
|
|||
}
|
||||
|
||||
/*
|
||||
* For scaling our actuators using anything less than the min (close to stall)
|
||||
* For scaling our actuators using anything less than the stall
|
||||
* speed doesn't make any sense - its the strongest reasonable deflection we
|
||||
* want to do in flight and its the baseline a human pilot would choose.
|
||||
*
|
||||
|
|
|
@ -145,7 +145,7 @@ FixedwingPositionControl::parameters_update()
|
|||
|
||||
// sanity check parameters
|
||||
if (_param_fw_airspd_max.get() < _param_fw_airspd_min.get()) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Config invalid: Airspeed min smaller than max");
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Config invalid: Airspeed max smaller than min");
|
||||
check_ret = PX4_ERROR;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue