From e67347f011793a841ff58d63917eb5766515c9f6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Mar 2020 11:51:15 +1100 Subject: [PATCH] AP_HAL_SITL: rename APMrover2 to Rover --- libraries/AP_HAL_SITL/SITL_State.cpp | 6 +++--- libraries/AP_HAL_SITL/SITL_State.h | 2 +- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 183642473b..6a68975580 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -630,7 +630,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input) if (_vehicle == ArduPlane) { pwm_output[0] = pwm_output[1] = pwm_output[3] = 1500; } - if (_vehicle == APMrover2) { + if (_vehicle == Rover) { pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500; } } @@ -695,7 +695,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input) engine_fail = 0; } // apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter - if (_vehicle != APMrover2) { + if (_vehicle != Rover) { input.servos[engine_fail] = ((input.servos[engine_fail]-1000) * engine_mul) + 1000; } else { input.servos[engine_fail] = static_cast(((input.servos[engine_fail] - 1500) * engine_mul) + 1500); @@ -722,7 +722,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input) } else { throttle = hover_throttle; } - } else if (_vehicle == APMrover2) { + } else if (_vehicle == Rover) { input.servos[2] = static_cast(constrain_int16(input.servos[2], 1000, 2000)); input.servos[0] = static_cast(constrain_int16(input.servos[0], 1000, 2000)); throttle = fabsf((input.servos[2] - 1500) / 500.0f); diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 6de7d67409..5ce3bab65a 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -54,7 +54,7 @@ public: enum vehicle_type { ArduCopter, - APMrover2, + Rover, ArduPlane, ArduSub }; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index f7d0caccde..c469e0b2b6 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -421,8 +421,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) if (_framerate == 0) { _framerate = 200; } - } else if (strcmp(SKETCH, "APMrover2") == 0) { - _vehicle = APMrover2; + } else if (strcmp(SKETCH, "Rover") == 0) { + _vehicle = Rover; if (_framerate == 0) { _framerate = 50; }