From 13b2b76cfe6e13c869397dddec0caa2de4150afd Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Thu, 9 Mar 2017 17:29:59 -0500 Subject: [PATCH] Sub: Enable circle nav parameters, and set default circle rate --- ArduSub/Parameters.cpp | 1 + ArduSub/config.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index a2f5ae837f..d94ec9356a 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -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) diff --git a/ArduSub/config.h b/ArduSub/config.h index 4aa466af78..078fa3af90 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -68,7 +68,7 @@ // #ifndef CIRCLE_NAV_ENABLED -# define CIRCLE_NAV_ENABLED DISABLED +# define CIRCLE_NAV_ENABLED ENABLED #endif //////////////////////////////////////////////////////////////////////////////