mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: althold remove redundant z-axis init
This commit is contained in:
parent
8ff8364252
commit
a3a1601837
@ -8,10 +8,6 @@
|
|||||||
// althold_init - initialise althold controller
|
// althold_init - initialise althold controller
|
||||||
bool Copter::ModeAltHold::init(bool ignore_checks)
|
bool Copter::ModeAltHold::init(bool ignore_checks)
|
||||||
{
|
{
|
||||||
// initialize vertical speeds and leash lengths
|
|
||||||
pos_control->set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
|
|
||||||
pos_control->set_accel_z(g.pilot_accel_z);
|
|
||||||
|
|
||||||
// initialise position and desired velocity
|
// initialise position and desired velocity
|
||||||
if (!pos_control->is_active_z()) {
|
if (!pos_control->is_active_z()) {
|
||||||
pos_control->set_alt_target_to_current_alt();
|
pos_control->set_alt_target_to_current_alt();
|
||||||
|
Loading…
Reference in New Issue
Block a user