Copter: minor typo in do_change_speed processing

It is unlikely that the "f" at the end of the 100 is required to
maintain the full precision of the target speed but added just in case
This commit is contained in:
Randy Mackay 2014-03-17 14:41:32 +09:00
parent 08b78db43c
commit a3573f9ebd

View File

@ -629,7 +629,7 @@ static bool do_guided(const AP_Mission::Mission_Command& cmd)
static void do_change_speed(const AP_Mission::Mission_Command& cmd)
{
wp_nav.set_horizontal_velocity(cmd.content.speed.target_ms * 100);
wp_nav.set_horizontal_velocity(cmd.content.speed.target_ms * 100.0f);
}
static void do_set_home(const AP_Mission::Mission_Command& cmd)