Sub: Enable circle nav parameters, and set default circle rate
This commit is contained in:
parent
7c552d3545
commit
13b2b76cfe
@ -894,6 +894,7 @@ void Sub::load_parameters(void)
|
|||||||
AP_Arming::ARMING_CHECK_VOLTAGE |
|
AP_Arming::ARMING_CHECK_VOLTAGE |
|
||||||
AP_Arming::ARMING_CHECK_BATTERY |
|
AP_Arming::ARMING_CHECK_BATTERY |
|
||||||
AP_Arming::ARMING_CHECK_LOGGING);
|
AP_Arming::ARMING_CHECK_LOGGING);
|
||||||
|
AP_Param::set_default_by_name("CIRCLE_RATE", 2.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sub::convert_old_parameters(void)
|
void Sub::convert_old_parameters(void)
|
||||||
|
@ -68,7 +68,7 @@
|
|||||||
//
|
//
|
||||||
|
|
||||||
#ifndef CIRCLE_NAV_ENABLED
|
#ifndef CIRCLE_NAV_ENABLED
|
||||||
# define CIRCLE_NAV_ENABLED DISABLED
|
# define CIRCLE_NAV_ENABLED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
Loading…
Reference in New Issue
Block a user