mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Updated Configs based on field testing.
This commit is contained in:
parent
15a377d759
commit
c7f93f8718
@ -367,7 +367,6 @@ static const float radius_of_earth = 6378100; // meters
|
|||||||
static const float gravity = 9.81; // meters/ sec^2
|
static const float gravity = 9.81; // meters/ sec^2
|
||||||
static int32_t target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
static int32_t target_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
||||||
static int32_t nav_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
static int32_t nav_bearing; // deg * 100 : 0 to 360 location of the plane to the target
|
||||||
|
|
||||||
static int32_t home_bearing; // used to track difference in angle
|
static int32_t home_bearing; // used to track difference in angle
|
||||||
|
|
||||||
static byte wp_control; // used to control - navgation or loiter
|
static byte wp_control; // used to control - navgation or loiter
|
||||||
|
@ -508,7 +508,7 @@
|
|||||||
|
|
||||||
|
|
||||||
#ifndef STABILIZE_D
|
#ifndef STABILIZE_D
|
||||||
# define STABILIZE_D .25
|
# define STABILIZE_D .2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Jasons default values that are good for smaller payload motors.
|
// Jasons default values that are good for smaller payload motors.
|
||||||
@ -606,17 +606,17 @@
|
|||||||
// Navigation control gains
|
// Navigation control gains
|
||||||
//
|
//
|
||||||
#ifndef LOITER_P
|
#ifndef LOITER_P
|
||||||
# define LOITER_P .2 // .3 was too aggressive
|
# define LOITER_P .25 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_I
|
#ifndef LOITER_I
|
||||||
# define LOITER_I 0.05 // Wind control
|
# define LOITER_I 0.1 // Wind control
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_IMAX
|
#ifndef LOITER_IMAX
|
||||||
# define LOITER_IMAX 30 // degrees°
|
# define LOITER_IMAX 30 // degrees°
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef NAV_P
|
#ifndef NAV_P
|
||||||
# define NAV_P 1.5 // 3 was causing rapid oscillations in Loiter
|
# define NAV_P 2.2 // 3 was causing rapid oscillations in Loiter
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_I
|
#ifndef NAV_I
|
||||||
# define NAV_I 0.15 // used in traverals
|
# define NAV_I 0.15 // used in traverals
|
||||||
@ -649,7 +649,7 @@
|
|||||||
|
|
||||||
// RATE control
|
// RATE control
|
||||||
#ifndef THROTTLE_P
|
#ifndef THROTTLE_P
|
||||||
# define THROTTLE_P 0.4 //
|
# define THROTTLE_P 0.5 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_I
|
#ifndef THROTTLE_I
|
||||||
# define THROTTLE_I 0.0 //
|
# define THROTTLE_I 0.0 //
|
||||||
@ -663,7 +663,7 @@
|
|||||||
// Crosstrack compensation
|
// Crosstrack compensation
|
||||||
//
|
//
|
||||||
#ifndef CROSSTRACK_GAIN
|
#ifndef CROSSTRACK_GAIN
|
||||||
# define CROSSTRACK_GAIN 40
|
# define CROSSTRACK_GAIN 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user