Plane: Allow reseting target airspeed to the parameter value
This commit is contained in:
parent
84986fda01
commit
d30891e3d1
@ -937,7 +937,11 @@ bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
|||||||
switch (cmd.content.speed.speed_type)
|
switch (cmd.content.speed.speed_type)
|
||||||
{
|
{
|
||||||
case 0: // Airspeed
|
case 0: // Airspeed
|
||||||
if ((cmd.content.speed.target_ms >= aparm.airspeed_min.get()) && (cmd.content.speed.target_ms <= aparm.airspeed_max.get())) {
|
if (is_equal(cmd.content.speed.target_ms, -2.0f)) {
|
||||||
|
new_airspeed_cm = -1; // return to default airspeed
|
||||||
|
return true;
|
||||||
|
} else if ((cmd.content.speed.target_ms >= aparm.airspeed_min.get()) &&
|
||||||
|
(cmd.content.speed.target_ms <= aparm.airspeed_max.get())) {
|
||||||
new_airspeed_cm = cmd.content.speed.target_ms * 100; //new airspeed target for AUTO or GUIDED modes
|
new_airspeed_cm = cmd.content.speed.target_ms * 100; //new airspeed target for AUTO or GUIDED modes
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms);
|
gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms);
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user