mirror of https://github.com/ArduPilot/ardupilot
Rover: move TURN_MAX_G param to atitude control
This commit is contained in:
parent
c5503b9aed
commit
c1d4e5116d
|
@ -217,15 +217,6 @@ const AP_Param::Info Rover::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(mode6, "MODE6", Mode::Number::MANUAL),
|
GSCALAR(mode6, "MODE6", Mode::Number::MANUAL),
|
||||||
|
|
||||||
// @Param: TURN_MAX_G
|
|
||||||
// @DisplayName: Turning maximum G force
|
|
||||||
// @Description: The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
|
|
||||||
// @Units: gravities
|
|
||||||
// @Range: 0.1 10
|
|
||||||
// @Increment: 0.01
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(turn_max_g, "TURN_MAX_G", 0.6f),
|
|
||||||
|
|
||||||
// variables not in the g class which contain EEPROM saved variables
|
// variables not in the g class which contain EEPROM saved variables
|
||||||
|
|
||||||
// @Group: COMPASS_
|
// @Group: COMPASS_
|
||||||
|
@ -754,6 +745,7 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
||||||
{ Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" },
|
{ Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" },
|
||||||
{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },
|
{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },
|
||||||
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
|
{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },
|
||||||
|
{ Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" },
|
||||||
};
|
};
|
||||||
|
|
||||||
void Rover::load_parameters(void)
|
void Rover::load_parameters(void)
|
||||||
|
|
|
@ -117,7 +117,7 @@ public:
|
||||||
k_param_auto_trigger_pin,
|
k_param_auto_trigger_pin,
|
||||||
k_param_auto_kickstart,
|
k_param_auto_kickstart,
|
||||||
k_param_turn_circle, // unused
|
k_param_turn_circle, // unused
|
||||||
k_param_turn_max_g,
|
k_param_turn_max_g_old, // unused
|
||||||
|
|
||||||
//
|
//
|
||||||
// 160: Radio settings
|
// 160: Radio settings
|
||||||
|
@ -239,7 +239,6 @@ public:
|
||||||
AP_Int8 ch7_option;
|
AP_Int8 ch7_option;
|
||||||
AP_Int8 auto_trigger_pin;
|
AP_Int8 auto_trigger_pin;
|
||||||
AP_Float auto_kickstart;
|
AP_Float auto_kickstart;
|
||||||
AP_Float turn_max_g;
|
|
||||||
AP_Int16 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
|
||||||
// Throttle
|
// Throttle
|
||||||
|
|
|
@ -371,7 +371,7 @@ void Rover::one_second_loop(void)
|
||||||
set_likely_flying(hal.util->get_soft_armed());
|
set_likely_flying(hal.util->get_soft_armed());
|
||||||
|
|
||||||
// send latest param values to wp_nav
|
// send latest param values to wp_nav
|
||||||
g2.wp_nav.set_turn_params(g.turn_max_g, g2.turn_radius, g2.motors.have_skid_steering());
|
g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::update_current_mode(void)
|
void Rover::update_current_mode(void)
|
||||||
|
|
|
@ -456,7 +456,7 @@ void Mode::calc_steering_from_turn_rate(float turn_rate)
|
||||||
void Mode::calc_steering_from_lateral_acceleration(float lat_accel, bool reversed)
|
void Mode::calc_steering_from_lateral_acceleration(float lat_accel, bool reversed)
|
||||||
{
|
{
|
||||||
// constrain to max G force
|
// constrain to max G force
|
||||||
lat_accel = constrain_float(lat_accel, -g.turn_max_g * GRAVITY_MSS, g.turn_max_g * GRAVITY_MSS);
|
lat_accel = constrain_float(lat_accel, -attitude_control.get_turn_lat_accel_max(), attitude_control.get_turn_lat_accel_max());
|
||||||
|
|
||||||
// send final steering command to motor library
|
// send final steering command to motor library
|
||||||
const float steering_out = attitude_control.get_steering_out_lat_accel(lat_accel,
|
const float steering_out = attitude_control.get_steering_out_lat_accel(lat_accel,
|
||||||
|
|
|
@ -36,7 +36,7 @@ void ModeSteering::update()
|
||||||
// For regular steering vehicles we use the maximum lateral acceleration
|
// For regular steering vehicles we use the maximum lateral acceleration
|
||||||
// at full steering lock for this speed: V^2/R where R is the radius of turn.
|
// at full steering lock for this speed: V^2/R where R is the radius of turn.
|
||||||
float max_g_force = speed * speed / MAX(g2.turn_radius, 0.1f);
|
float max_g_force = speed * speed / MAX(g2.turn_radius, 0.1f);
|
||||||
max_g_force = constrain_float(max_g_force, 0.1f, g.turn_max_g * GRAVITY_MSS);
|
max_g_force = constrain_float(max_g_force, 0.1f, attitude_control.get_turn_lat_accel_max());
|
||||||
|
|
||||||
// convert pilot steering input to desired lateral acceleration
|
// convert pilot steering input to desired lateral acceleration
|
||||||
_desired_lat_accel = max_g_force * (desired_steering / 4500.0f);
|
_desired_lat_accel = max_g_force * (desired_steering / 4500.0f);
|
||||||
|
|
Loading…
Reference in New Issue