Browse Source

Copter: integrate AC_WPNav get_speed_xy name change

master
Randy Mackay 11 years ago
parent
commit
466e9db1f9
  1. 2
      ArduCopter/ArduCopter.pde
  2. 2
      ArduCopter/commands_logic.pde

2
ArduCopter/ArduCopter.pde

@ -1448,7 +1448,7 @@ static void tuning(){ @@ -1448,7 +1448,7 @@ static void tuning(){
case CH6_WP_SPEED:
// 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;
// Acro roll pitch gain

2
ArduCopter/commands_logic.pde

@ -794,7 +794,7 @@ static bool do_guided(const AP_Mission::Mission_Command& cmd) @@ -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)
{
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…
Cancel
Save