mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: set-desired-speed applied to flightmode
This commit is contained in:
parent
97ab37875e
commit
5718c49928
@ -404,13 +404,7 @@ bool Copter::set_circle_rate(float rate_dps)
|
|||||||
// set desired speed (m/s). Used for scripting.
|
// set desired speed (m/s). Used for scripting.
|
||||||
bool Copter::set_desired_speed(float speed)
|
bool Copter::set_desired_speed(float speed)
|
||||||
{
|
{
|
||||||
// exit if vehicle is not in auto mode
|
return flightmode->set_speed_xy(speed * 100.0f);
|
||||||
if (!flightmode->is_autopilot()) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
wp_nav->set_speed_xy(speed * 100.0f);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user