From 8c034e6fa21d962e0829836d2bbb0419c720a2a4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 9 May 2019 20:22:51 +0900 Subject: [PATCH] Rover: prepend _old to some unused param enums --- APMrover2/Parameters.cpp | 6 +++--- APMrover2/Parameters.h | 8 ++++---- APMrover2/mode.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 2334c9cafe..e9ebddacb2 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -777,9 +777,9 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" }, { Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" }, - { Parameters::k_param_pivot_turn_angle, 0, AP_PARAM_INT16, "WP_PIVOT_ANGLE" }, - { Parameters::k_param_waypoint_radius, 0, AP_PARAM_FLOAT, "WP_RADIUS" }, - { Parameters::k_param_waypoint_overshoot, 0, AP_PARAM_FLOAT, "WP_OVERSHOOT" }, + { Parameters::k_param_pivot_turn_angle_old, 0, AP_PARAM_INT16, "WP_PIVOT_ANGLE" }, + { Parameters::k_param_waypoint_radius_old, 0, AP_PARAM_FLOAT, "WP_RADIUS" }, + { Parameters::k_param_waypoint_overshoot_old, 0, AP_PARAM_FLOAT, "WP_OVERSHOOT" }, { Parameters::k_param_g2, 20, AP_PARAM_INT16, "WP_PIVOT_RATE" }, }; diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 5778beede3..db6680308b 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -36,7 +36,7 @@ public: k_param_scheduler, k_param_relay, k_param_BoardConfig, - k_param_pivot_turn_angle, // unused + k_param_pivot_turn_angle_old, // unused k_param_rc_13_old, // unused k_param_rc_14_old, // unused @@ -173,8 +173,8 @@ public: // k_param_command_total = 220, // unused k_param_command_index, // unused - k_param_waypoint_radius, // unused - k_param_waypoint_overshoot, // unused + k_param_waypoint_radius_old, // unused + k_param_waypoint_overshoot_old, // unused // // camera control @@ -324,7 +324,7 @@ public: // Safe RTL library AP_SmartRTL smart_rtl; - // default speeds for rtl + // default speed for rtl AP_Float rtl_speed; // frame class for vehicle diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index d5f3877c6e..277a106628 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -220,7 +220,7 @@ void Mode::set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) _desired_speed = target_speed; } -// get default speed for this mode (held in (WP_SPEED or RTL_SPEED) +// get default speed for this mode (held in WP_SPEED or RTL_SPEED) float Mode::get_speed_default(bool rtl) const { if (rtl && is_positive(g2.rtl_speed)) {