From 33e47e203677e6fbe10504a393bd5392fded6eeb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Dec 2012 15:42:11 +1100 Subject: [PATCH] Rover: set throttle range from -100 to 100 this allows for reverse --- APMrover2/Attitude.pde | 10 +++++----- APMrover2/GCS_Mavlink.pde | 2 +- APMrover2/radio.pde | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/APMrover2/Attitude.pde b/APMrover2/Attitude.pde index 690504a634..6185fc8e7a 100644 --- a/APMrover2/Attitude.pde +++ b/APMrover2/Attitude.pde @@ -33,9 +33,9 @@ static void throttle_slew_limit(int16_t last_throttle) } static void calc_throttle() -{ int rov_speed; - - int throttle_target = g.throttle_cruise + throttle_nudge + 50; +{ + int rov_speed; + int throttle_target = g.throttle_cruise + throttle_nudge; rov_speed = g.airspeed_cruise; @@ -44,8 +44,8 @@ static void calc_throttle() groundspeed_error = rov_speed - (float)ground_speed; - throttle = (throttle_target + g.pidTeThrottle.get_pid(groundspeed_error)) * 10; - g.channel_throttle.servo_out = constrain(((float)throttle / 10.0f), 0, g.throttle_max.get()); + throttle = throttle_target + g.pidTeThrottle.get_pid(groundspeed_error); + g.channel_throttle.servo_out = constrain(throttle, 0, g.throttle_max.get()); } /***************************************** diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 72b48d428c..9d0067cb67 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -329,7 +329,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan) (float)g_gps->ground_speed / 100.0, (float)g_gps->ground_speed / 100.0, (ahrs.yaw_sensor / 100) % 360, - (uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100 + (uint16_t)(100 * g.channel_throttle.norm_output()), current_loc.alt / 100.0, 0); } diff --git a/APMrover2/radio.pde b/APMrover2/radio.pde index a2a2bb97ef..65070aee59 100644 --- a/APMrover2/radio.pde +++ b/APMrover2/radio.pde @@ -11,7 +11,7 @@ static void init_rc_in() g.channel_roll.set_angle(SERVO_MAX); g.channel_pitch.set_angle(SERVO_MAX); g.channel_rudder.set_angle(SERVO_MAX); - g.channel_throttle.set_range(0, 100); + g.channel_throttle.set_angle(100); // set rc dead zones g.channel_roll.set_dead_zone(60);