Rover: remove THR_MIN, THR_MAX parameters from vehicle

enforcing these limits is now handled by AP_MotorsUGV class
This commit is contained in:
Randy Mackay 2017-08-16 10:32:56 +09:00
parent c0fe1b7ec8
commit 167a856cdb
4 changed files with 9 additions and 35 deletions

View File

@ -139,24 +139,6 @@ const AP_Param::Info Rover::var_info[] = {
// @User: Standard
GSCALAR(ch7_option, "CH7_OPTION", CH7_OPTION),
// @Param: THR_MIN
// @DisplayName: Minimum Throttle
// @Description: The minimum throttle setting to which the autopilot will apply. This is mostly useful for rovers with internal combustion motors, to prevent the motor from cutting out in auto mode.
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
// @Param: THR_MAX
// @DisplayName: Maximum Throttle
// @Description: The maximum throttle setting to which the autopilot will apply. This can be used to prevent overheating a ESC or motor on an electric rover.
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
// @Param: CRUISE_THROTTLE
// @DisplayName: Base throttle percentage in auto
// @Description: The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.
@ -568,6 +550,8 @@ const AP_Param::ConversionInfo conversion_table[] = {
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
{ Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" },
{ Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" },
};
void Rover::load_parameters(void)

View File

@ -124,8 +124,8 @@ public:
k_param_rc_8_old,
// throttle control
k_param_throttle_min = 170,
k_param_throttle_max,
k_param_throttle_min_old = 170, // unused
k_param_throttle_max_old, // unused
k_param_throttle_cruise,
k_param_throttle_slewrate_old, // unused
k_param_throttle_reduction, // unused
@ -238,8 +238,6 @@ public:
// Throttle
//
AP_Int8 throttle_min;
AP_Int8 throttle_max;
AP_Int8 throttle_cruise;
AP_Int8 skid_steer_in;

View File

@ -74,12 +74,8 @@ void Mode::calc_throttle(float target_speed, bool nudge_allowed)
// call throttle controller and convert output to -100 to +100 range
float throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, g2.motors.have_skid_steering(), g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise / 100.0f);
// apply limits on throttle
if (is_negative(throttle_out)) {
g2.motors.set_throttle(constrain_float(throttle_out, -g.throttle_max, -g.throttle_min));
} else {
g2.motors.set_throttle(constrain_float(throttle_out, g.throttle_min, g.throttle_max));
}
// send to motor
g2.motors.set_throttle(throttle_out);
}
// performs a controlled stop with steering centered
@ -89,12 +85,8 @@ bool Mode::stop_vehicle()
bool stopped = false;
float throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.have_skid_steering(), g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise / 100.0f, stopped);
// apply limits on throttle
if (is_negative(throttle_out)) {
g2.motors.set_throttle(constrain_float(throttle_out, -g.throttle_max, -g.throttle_min));
} else {
g2.motors.set_throttle(constrain_float(throttle_out, g.throttle_min, g.throttle_max));
}
// send to motor
g2.motors.set_throttle(throttle_out);
// do not attempt to steer
g2.motors.set_steering(0.0f);

View File

@ -10,7 +10,7 @@ void ModeSteering::update()
float speed;
if (!attitude_control.get_forward_speed(speed)) {
// no valid speed so stop
g2.motors.set_throttle(g.throttle_min.get());
g2.motors.set_throttle(0.0f);
g2.motors.set_steering(0.0f);
lateral_acceleration = 0.0f;
return;