mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_L1_Control: set min groundspeed to 0.1
this works better for slow rovers
This commit is contained in:
parent
c6e37aaec3
commit
144516c941
@ -111,11 +111,11 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||||||
|
|
||||||
//Calculate groundspeed
|
//Calculate groundspeed
|
||||||
float groundSpeed = _groundspeed_vector.length();
|
float groundSpeed = _groundspeed_vector.length();
|
||||||
if (groundSpeed < 1.0f) {
|
if (groundSpeed < 0.1f) {
|
||||||
// use a small ground speed vector in the right direction,
|
// use a small ground speed vector in the right direction,
|
||||||
// allowing us to use the compass heading at zero GPS velocity
|
// allowing us to use the compass heading at zero GPS velocity
|
||||||
_groundspeed_vector = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw));
|
groundSpeed = 0.1f;
|
||||||
groundSpeed = 1.0f;
|
_groundspeed_vector = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw)) * groundSpeed;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Calculate time varying control parameters
|
// Calculate time varying control parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user