From d5f3cf50e46332cfbda3b65d7c9eb0ad55f14b30 Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Tue, 7 May 2019 19:20:43 +0100 Subject: [PATCH] Rover: Parmeters: remove old sailboat params --- APMrover2/Parameters.cpp | 60 +++++----------------------------------- APMrover2/Parameters.h | 10 ++----- 2 files changed, 10 insertions(+), 60 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index e9ebddacb2..77b9be7253 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -585,50 +585,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AP_WindVane/AP_WindVane.cpp AP_SUBGROUPINFO(windvane, "WNDVN_", 31, ParametersG2, AP_WindVane), - // @Param: SAIL_ANGLE_MIN - // @DisplayName: Sail min angle - // @Description: Mainsheet tight, angle between centerline and boom - // @Units: deg - // @Range: 0 90 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("SAIL_ANGLE_MIN", 32, ParametersG2, sail_angle_min, 0), - - // @Param: SAIL_ANGLE_MAX - // @DisplayName: Sail max angle - // @Description: Mainsheet loose, angle between centerline and boom - // @Units: deg - // @Range: 0 90 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("SAIL_ANGLE_MAX", 33, ParametersG2, sail_angle_max, 90), - - // @Param: SAIL_ANGLE_IDEAL - // @DisplayName: Sail ideal angle - // @Description: Ideal angle between sail and apparent wind - // @Units: deg - // @Range: 0 90 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("SAIL_ANGLE_IDEAL", 34, ParametersG2, sail_angle_ideal, 25), - - // @Param: SAIL_HEEL_MAX - // @DisplayName: Sailing maximum heel angle - // @Description: When in auto sail trim modes the heel will be limited to this value using PID control - // @Units: deg - // @Range: 0 90 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("SAIL_HEEL_MAX", 35, ParametersG2, sail_heel_angle_max, 15), - - // @Param: SAIL_NO_GO_ANGLE - // @DisplayName: Sailing no go zone angle - // @Description: The typical closest angle to the wind the vehicle will sail at. the vehicle will sail at this angle when going upwind - // @Units: deg - // @Range: 0 90 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("SAIL_NO_GO_ANGLE", 36, ParametersG2, sail_no_go, 45), + // 32 to 36 were old sailboat params // @Group: ARSPD // @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp @@ -672,6 +629,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AR_WPNav/AR_WPNav.cpp AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav), + // @Group: SAIL_ + // @Path: sailboat.cpp + AP_SUBGROUPINFO(sailboat, "SAIL_", 44, ParametersG2, Sailboat), + AP_GROUPEND }; @@ -744,7 +705,8 @@ ParametersG2::ParametersG2(void) follow(), windvane(), airspeed(), - wp_nav(attitude_control, rover.L1_controller) + wp_nav(attitude_control, rover.L1_controller), + sailboat() { AP_Param::setup_object_defaults(this, var_info); } @@ -817,14 +779,6 @@ void Rover::load_parameters(void) g2.crash_angle.set_default(30); } - // sailboat defaults - if (g2.motors.has_sail()) { - g2.crash_angle.set_default(0); - g2.loit_type.set_default(1); - g2.loit_radius.set_default(5); - g2.wp_nav.set_default_overshoot(10); - } - const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old, Parameters::k_param_rc_3_old, Parameters::k_param_rc_4_old, Parameters::k_param_rc_5_old, Parameters::k_param_rc_6_old, diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index db6680308b..d3d471dd78 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -368,13 +368,6 @@ public: // Simple mode types AP_Int8 simple_type; - // sailboat parameters - AP_Float sail_angle_min; - AP_Float sail_angle_max; - AP_Float sail_angle_ideal; - AP_Float sail_heel_angle_max; - AP_Float sail_no_go; - // windvane AP_WindVane windvane; @@ -396,6 +389,9 @@ public: // waypoint navigation AR_WPNav wp_nav; + + // Sailboat functions + Sailboat sailboat; }; extern const AP_Param::Info var_info[];