From 521918d74ca4c7369e0730063ea376ef0632c3af Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Oct 2021 09:48:47 +1100 Subject: [PATCH] SITL: remove set-but-not-used _framerate member variable --- libraries/AP_HAL_SITL/SITL_State.h | 1 - libraries/AP_HAL_SITL/SITL_cmdline.cpp | 12 ------------ 2 files changed, 13 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 58327511b0..9dd54a454f 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -191,7 +191,6 @@ private: // internal state enum vehicle_type _vehicle; - uint16_t _framerate; uint8_t _instance; uint16_t _base_port; pid_t _parent_pid; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 6b7a778dec..8c122c3743 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -361,9 +361,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) cmdline_param.push_back(temp_cmdline_param); printf("Setting SIM_SPEEDUP=%f\n", speedup); break; - case 'r': - _framerate = (unsigned)atoi(gopt.optarg); - break; case 'C': HALSITL::UARTDriver::_console = true; break; @@ -571,14 +568,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) if (strcmp(SKETCH, "ArduCopter") == 0) { _vehicle = ArduCopter; - if (_framerate == 0) { - _framerate = 200; - } } else if (strcmp(SKETCH, "Rover") == 0) { _vehicle = Rover; - if (_framerate == 0) { - _framerate = 50; - } // set right default throttle for rover (allowing for reverse) pwm_input[2] = 1500; } else if (strcmp(SKETCH, "ArduSub") == 0) { @@ -593,9 +584,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) } } else { _vehicle = ArduPlane; - if (_framerate == 0) { - _framerate = 50; - } } _sitl_setup(home_str);