mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: added experimental LOITER_REPOSITIONING #define to config.h
APM_Config.h should be used to overriding the standard parameters but they still require a definition in config.h or they will be undefined when built by the mission planner.
This commit is contained in:
parent
381bd28518
commit
0830eaf363
@ -69,6 +69,5 @@
|
||||
|
||||
//#define LOGGING_ENABLED DISABLED
|
||||
|
||||
#define LOITER_REPOSITIONING DISABLED // Experimental Do Not Use
|
||||
// #define LOITER_REPOSITIONING ENABLED // Experimental Do Not Use
|
||||
// #define LOITER_RP ROLL_PITCH_LOITER_PR
|
||||
|
||||
|
@ -658,7 +658,7 @@
|
||||
|
||||
|
||||
|
||||
// LOITER Mode
|
||||
// Optical Flow LOITER Mode
|
||||
#ifndef OF_LOITER_YAW
|
||||
# define OF_LOITER_YAW YAW_HOLD
|
||||
#endif
|
||||
@ -830,6 +830,11 @@
|
||||
#ifndef LOITER_IMAX
|
||||
# define LOITER_IMAX 30 // degrees
|
||||
#endif
|
||||
|
||||
// Loiter repositioning configuration (experimental)
|
||||
#ifndef LOITER_REPOSITIONING
|
||||
# define LOITER_REPOSITIONING DISABLED
|
||||
#endif
|
||||
#ifndef LOITER_REPOSITION_RATE
|
||||
# define LOITER_REPOSITION_RATE 500.0 // cm/s
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user