From e9e1dac188325f4818db9122984695e29b8b17dd Mon Sep 17 00:00:00 2001 From: khancyr Date: Wed, 8 Nov 2017 15:40:14 +0900 Subject: [PATCH] AR_AttitudeControl: remove unused skid_steering arg from get_throttle_out --- libraries/APM_Control/AR_AttitudeControl.cpp | 7 +++---- libraries/APM_Control/AR_AttitudeControl.h | 5 ++--- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 515466b286..f7c099e8e5 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -240,10 +240,9 @@ float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool skid_st } // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards) -// skid_steering should be true for skid-steer vehicles // motor_limit should be true if motors have hit their upper or lower limits // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1 -float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool skid_steering, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle) +float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle) { // get speed forward float speed; @@ -325,7 +324,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool skid_ } // return a throttle output from -1 to +1 to perform a controlled stop. returns true once the vehicle has stopped -float AR_AttitudeControl::get_throttle_out_stop(bool skid_steering, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, bool &stopped) +float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, bool &stopped) { // get current system time uint32_t now = AP_HAL::millis(); @@ -357,7 +356,7 @@ float AR_AttitudeControl::get_throttle_out_stop(bool skid_steering, bool motor_l // clear stopped system time _stop_last_ms = 0; // run speed controller to bring vehicle to stop - return get_throttle_out_speed(0.0f, skid_steering, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle); + return get_throttle_out_speed(0.0f, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle); } } diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index 86997caabf..31eca76ee5 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -60,13 +60,12 @@ public: void set_throttle_limits(float throttle_accel_max, float throttle_decel_max); // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards) - // skid_steering should be true for skid-steer vehicles // motor_limit should be true if motors have hit their upper or lower limits // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1 - float get_throttle_out_speed(float desired_speed, bool skid_steering, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle); + float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle); // return a throttle output from -1 to +1 to perform a controlled stop. stopped is set to true once stop has been completed - float get_throttle_out_stop(bool skid_steering, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, bool &stopped); + float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, bool &stopped); // low level control accessors for reporting and logging AC_P& get_steering_angle_p() { return _steer_angle_p; }