Copter: initialise vertical speed for Loiter mode
This commit is contained in:
parent
dd45647626
commit
0d23c3b910
@ -8,10 +8,16 @@
|
|||||||
static bool loiter_init(bool ignore_checks)
|
static bool loiter_init(bool ignore_checks)
|
||||||
{
|
{
|
||||||
if (GPS_ok() || ignore_checks) {
|
if (GPS_ok() || ignore_checks) {
|
||||||
|
|
||||||
// set target to current position
|
// set target to current position
|
||||||
wp_nav.init_loiter_target();
|
wp_nav.init_loiter_target();
|
||||||
|
|
||||||
|
// initialize vertical speeds
|
||||||
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||||
|
|
||||||
// initialise altitude target to stopping point
|
// initialise altitude target to stopping point
|
||||||
pos_control.set_target_to_stopping_point_z();
|
pos_control.set_target_to_stopping_point_z();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}else{
|
}else{
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user