Copter: integrate WPNAV::set_speed_z split to set_speed_up and set_speed_down
This commit is contained in:
parent
717fb4d823
commit
42c7f5ceb4
@ -729,9 +729,9 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
// param4 : unused
|
||||
if (packet.param2 > 0.0f) {
|
||||
if (packet.param1 > 2.9f) { // 3 = speed down
|
||||
copter.wp_nav->set_speed_z(packet.param2 * 100.0f, copter.wp_nav->get_speed_up());
|
||||
copter.wp_nav->set_speed_down(packet.param2 * 100.0f);
|
||||
} else if (packet.param1 > 1.9f) { // 2 = speed up
|
||||
copter.wp_nav->set_speed_z(copter.wp_nav->get_speed_down(), packet.param2 * 100.0f);
|
||||
copter.wp_nav->set_speed_up(packet.param2 * 100.0f);
|
||||
} else {
|
||||
copter.wp_nav->set_speed_xy(packet.param2 * 100.0f);
|
||||
}
|
||||
|
@ -1355,9 +1355,9 @@ void Copter::ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
if (cmd.content.speed.target_ms > 0) {
|
||||
if (cmd.content.speed.speed_type == 2) {
|
||||
copter.wp_nav->set_speed_z(copter.wp_nav->get_speed_down(), cmd.content.speed.target_ms * 100.0f);
|
||||
copter.wp_nav->set_speed_up(cmd.content.speed.target_ms * 100.0f);
|
||||
} else if (cmd.content.speed.speed_type == 3) {
|
||||
copter.wp_nav->set_speed_z(cmd.content.speed.target_ms * 100.0f, copter.wp_nav->get_speed_up());
|
||||
copter.wp_nav->set_speed_down(cmd.content.speed.target_ms * 100.0f);
|
||||
} else {
|
||||
copter.wp_nav->set_speed_xy(cmd.content.speed.target_ms * 100.0f);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user