Sub: Enable circle nav parameters, and set default circle rate

This commit is contained in:
Jacob Walser 2017-03-09 17:29:59 -05:00 committed by Randy Mackay
parent 7c552d3545
commit 13b2b76cfe
2 changed files with 2 additions and 1 deletions

View File

@ -894,6 +894,7 @@ void Sub::load_parameters(void)
AP_Arming::ARMING_CHECK_VOLTAGE |
AP_Arming::ARMING_CHECK_BATTERY |
AP_Arming::ARMING_CHECK_LOGGING);
AP_Param::set_default_by_name("CIRCLE_RATE", 2.0f);
}
void Sub::convert_old_parameters(void)

View File

@ -68,7 +68,7 @@
//
#ifndef CIRCLE_NAV_ENABLED
# define CIRCLE_NAV_ENABLED DISABLED
# define CIRCLE_NAV_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////