mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Rover: removed unused code
thanks to Mike for noticing this
This commit is contained in:
parent
d3088b230a
commit
37b8686f76
@ -144,13 +144,6 @@ static void calc_lateral_acceleration()
|
||||
*/
|
||||
static void calc_nav_steer()
|
||||
{
|
||||
float speed = g_gps->ground_speed_cm * 0.01f;
|
||||
|
||||
if (speed < 1.0f) {
|
||||
// gps speed isn't very accurate at low speed
|
||||
speed = 1.0f;
|
||||
}
|
||||
|
||||
// add in obstacle avoidance
|
||||
lateral_acceleration += (obstacle.turn_angle/45.0f) * g.turn_max_g;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user