mirror of https://github.com/ArduPilot/ardupilot
Rover: integrate rename of AR_WPNav::set_speed_max
range checks are no longer required because they are implemented within AR_WPNav
This commit is contained in:
parent
a5638f5699
commit
5341070af4
|
@ -250,11 +250,7 @@ bool ModeAuto::set_desired_speed(float speed)
|
||||||
switch (_submode) {
|
switch (_submode) {
|
||||||
case Auto_WP:
|
case Auto_WP:
|
||||||
case Auto_Stop:
|
case Auto_Stop:
|
||||||
if (!is_negative(speed)) {
|
return g2.wp_nav.set_speed_max(speed);
|
||||||
g2.wp_nav.set_desired_speed(speed);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
case Auto_HeadingAndSpeed:
|
case Auto_HeadingAndSpeed:
|
||||||
_desired_speed = speed;
|
_desired_speed = speed;
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -262,11 +262,7 @@ bool ModeGuided::set_desired_speed(float speed)
|
||||||
{
|
{
|
||||||
switch (_guided_mode) {
|
switch (_guided_mode) {
|
||||||
case Guided_WP:
|
case Guided_WP:
|
||||||
if (!is_negative(speed)) {
|
return g2.wp_nav.set_speed_max(speed);
|
||||||
g2.wp_nav.set_desired_speed(speed);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
case Guided_HeadingAndSpeed:
|
case Guided_HeadingAndSpeed:
|
||||||
case Guided_TurnRateAndSpeed:
|
case Guided_TurnRateAndSpeed:
|
||||||
// speed is set from mavlink message
|
// speed is set from mavlink message
|
||||||
|
@ -327,7 +323,7 @@ bool ModeGuided::set_desired_location(const Location &destination, Location next
|
||||||
// handle guided specific initialisation and logging
|
// handle guided specific initialisation and logging
|
||||||
_guided_mode = ModeGuided::Guided_WP;
|
_guided_mode = ModeGuided::Guided_WP;
|
||||||
send_notification = true;
|
send_notification = true;
|
||||||
rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_desired_speed(), 0.0f, 0.0f));
|
rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -81,9 +81,5 @@ bool ModeRTL::reached_destination() const
|
||||||
// set desired speed in m/s
|
// set desired speed in m/s
|
||||||
bool ModeRTL::set_desired_speed(float speed)
|
bool ModeRTL::set_desired_speed(float speed)
|
||||||
{
|
{
|
||||||
if (is_negative(speed)) {
|
return g2.wp_nav.set_speed_max(speed);
|
||||||
return false;
|
|
||||||
}
|
|
||||||
g2.wp_nav.set_desired_speed(speed);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -127,11 +127,7 @@ bool ModeSmartRTL::get_desired_location(Location& destination) const
|
||||||
// set desired speed in m/s
|
// set desired speed in m/s
|
||||||
bool ModeSmartRTL::set_desired_speed(float speed)
|
bool ModeSmartRTL::set_desired_speed(float speed)
|
||||||
{
|
{
|
||||||
if (is_negative(speed)) {
|
return g2.wp_nav.set_speed_max(speed);
|
||||||
return false;
|
|
||||||
}
|
|
||||||
g2.wp_nav.set_desired_speed(speed);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// save current position for use by the smart_rtl flight mode
|
// save current position for use by the smart_rtl flight mode
|
||||||
|
|
Loading…
Reference in New Issue