mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: added basic support for reverse in STEERING mode
this will allow for reverse in steering mode, while also fixing a problem with AHRS yaw when reversing, and a problem with initial throttle in steering mode
This commit is contained in:
parent
56f574684d
commit
7046f44443
@ -537,6 +537,9 @@ static uint32_t delta_us_fast_loop;
|
|||||||
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
// Counter of main loop executions. Used for performance monitoring and failsafe processing
|
||||||
static uint16_t mainLoop_count;
|
static uint16_t mainLoop_count;
|
||||||
|
|
||||||
|
// set if we are driving backwards
|
||||||
|
static bool in_reverse;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Top-level logic
|
// Top-level logic
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -636,6 +639,12 @@ static void ahrs_update()
|
|||||||
gcs_update();
|
gcs_update();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// when in reverse we need to tell AHRS not to assume we are a
|
||||||
|
// 'fly forward' vehicle, otherwise it will see a large
|
||||||
|
// discrepancy between the mag and the GPS heading and will try to
|
||||||
|
// correct for it, leading to a large yaw error
|
||||||
|
ahrs.set_fly_forward(!in_reverse);
|
||||||
|
|
||||||
ahrs.update();
|
ahrs.update();
|
||||||
|
|
||||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
|
||||||
@ -860,7 +869,12 @@ static void update_current_mode(void)
|
|||||||
// and throttle gives speed in proportion to cruise speed, up
|
// and throttle gives speed in proportion to cruise speed, up
|
||||||
// to 50% throttle, then uses nudging above that.
|
// to 50% throttle, then uses nudging above that.
|
||||||
float target_speed = channel_throttle->pwm_to_angle() * 0.01 * 2 * g.speed_cruise;
|
float target_speed = channel_throttle->pwm_to_angle() * 0.01 * 2 * g.speed_cruise;
|
||||||
|
in_reverse = (target_speed < 0);
|
||||||
|
if (in_reverse) {
|
||||||
|
target_speed = constrain_float(target_speed, -g.speed_cruise, 0);
|
||||||
|
} else {
|
||||||
target_speed = constrain_float(target_speed, 0, g.speed_cruise);
|
target_speed = constrain_float(target_speed, 0, g.speed_cruise);
|
||||||
|
}
|
||||||
calc_throttle(target_speed);
|
calc_throttle(target_speed);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -875,6 +889,10 @@ static void update_current_mode(void)
|
|||||||
*/
|
*/
|
||||||
channel_throttle->servo_out = channel_throttle->control_in;
|
channel_throttle->servo_out = channel_throttle->control_in;
|
||||||
channel_steer->servo_out = channel_steer->pwm_to_angle();
|
channel_steer->servo_out = channel_steer->pwm_to_angle();
|
||||||
|
|
||||||
|
// mark us as in_reverse when using a negative throttle to
|
||||||
|
// stop AHRS getting off
|
||||||
|
in_reverse = (channel_throttle->servo_out < 0);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case HOLD:
|
case HOLD:
|
||||||
|
@ -75,13 +75,8 @@ static void calc_throttle(float target_speed)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (target_speed <= 0) {
|
float throttle_base = (fabsf(target_speed) / g.speed_cruise) * g.throttle_cruise;
|
||||||
// cope with zero requested speed
|
int throttle_target = throttle_base + throttle_nudge;
|
||||||
channel_throttle->servo_out = g.throttle_min.get();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
int throttle_target = g.throttle_cruise + throttle_nudge;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
reduce target speed in proportion to turning rate, up to the
|
reduce target speed in proportion to turning rate, up to the
|
||||||
@ -102,7 +97,7 @@ static void calc_throttle(float target_speed)
|
|||||||
// reduce the target speed by the reduction factor
|
// reduce the target speed by the reduction factor
|
||||||
target_speed *= reduction;
|
target_speed *= reduction;
|
||||||
|
|
||||||
groundspeed_error = target_speed - ground_speed;
|
groundspeed_error = fabsf(target_speed) - ground_speed;
|
||||||
|
|
||||||
throttle = throttle_target + (g.pidSpeedThrottle.get_pid(groundspeed_error * 100) / 100);
|
throttle = throttle_target + (g.pidSpeedThrottle.get_pid(groundspeed_error * 100) / 100);
|
||||||
|
|
||||||
@ -110,7 +105,11 @@ static void calc_throttle(float target_speed)
|
|||||||
// much faster response in turns
|
// much faster response in turns
|
||||||
throttle *= reduction;
|
throttle *= reduction;
|
||||||
|
|
||||||
channel_throttle->servo_out = constrain_int16(throttle, g.throttle_min.get(), g.throttle_max.get());
|
if (in_reverse) {
|
||||||
|
channel_throttle->servo_out = constrain_int16(-throttle, -g.throttle_max, -g.throttle_min);
|
||||||
|
} else {
|
||||||
|
channel_throttle->servo_out = constrain_int16(throttle, g.throttle_min, g.throttle_max);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*****************************************
|
/*****************************************
|
||||||
@ -179,9 +178,15 @@ static void set_servos(void)
|
|||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
channel_steer->calc_pwm();
|
channel_steer->calc_pwm();
|
||||||
|
if (in_reverse) {
|
||||||
|
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
|
||||||
|
-g.throttle_max,
|
||||||
|
-g.throttle_min);
|
||||||
|
} else {
|
||||||
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
|
channel_throttle->servo_out = constrain_int16(channel_throttle->servo_out,
|
||||||
g.throttle_min.get(),
|
g.throttle_min.get(),
|
||||||
g.throttle_max.get());
|
g.throttle_max.get());
|
||||||
|
}
|
||||||
|
|
||||||
if ((failsafe.bits & FAILSAFE_EVENT_THROTTLE) && control_mode < AUTO) {
|
if ((failsafe.bits & FAILSAFE_EVENT_THROTTLE) && control_mode < AUTO) {
|
||||||
// suppress throttle if in failsafe
|
// suppress throttle if in failsafe
|
||||||
|
@ -252,6 +252,8 @@ static void set_mode(enum mode mode)
|
|||||||
control_mode = mode;
|
control_mode = mode;
|
||||||
throttle_last = 0;
|
throttle_last = 0;
|
||||||
throttle = 500;
|
throttle = 500;
|
||||||
|
in_reverse = false;
|
||||||
|
g.pidSpeedThrottle.reset_I();
|
||||||
|
|
||||||
if (control_mode != AUTO) {
|
if (control_mode != AUTO) {
|
||||||
auto_triggered = false;
|
auto_triggered = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user