mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-08 06:34:22 -04:00
Copter: integrate AC_WPNav get_speed_xy name change
This commit is contained in:
parent
510c9920a6
commit
466e9db1f9
ArduCopter
@ -1448,7 +1448,7 @@ static void tuning(){
|
|||||||
|
|
||||||
case CH6_WP_SPEED:
|
case CH6_WP_SPEED:
|
||||||
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
|
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
|
||||||
wp_nav.set_horizontal_velocity(g.rc_6.control_in);
|
wp_nav.set_speed_xy(g.rc_6.control_in);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// Acro roll pitch gain
|
// Acro roll pitch gain
|
||||||
|
@ -794,7 +794,7 @@ static bool do_guided(const AP_Mission::Mission_Command& cmd)
|
|||||||
static void do_change_speed(const AP_Mission::Mission_Command& cmd)
|
static void do_change_speed(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
if (cmd.content.speed.target_ms > 0) {
|
if (cmd.content.speed.target_ms > 0) {
|
||||||
wp_nav.set_horizontal_velocity(cmd.content.speed.target_ms * 100.0f);
|
wp_nav.set_speed_xy(cmd.content.speed.target_ms * 100.0f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user