Rover: add turn radius param for steering mode

removes reliance on old steerController
This commit is contained in:
Randy Mackay 2017-08-10 17:29:21 +09:00
parent 9097269d6d
commit 61d1ced7aa
3 changed files with 13 additions and 1 deletions

View File

@ -532,6 +532,15 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/APM_Control/AR_AttitudeControl.cpp
AP_SUBGROUPINFO(attitude_control, "ATC", 10, ParametersG2, AR_AttitudeControl),
// @Param: TURN_RADIUS
// @DisplayName: Turn radius of vehicle
// @Description: Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
// @Units: m
// @Range: 0 10
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("TURN_RADIUS", 11, ParametersG2, turn_radius, 0.9),
AP_GROUPEND
};

View File

@ -326,6 +326,9 @@ public:
// steering and throttle controller
AR_AttitudeControl attitude_control;
// turn radius of vehicle (only used in steering mode)
AP_Float turn_radius;
};
extern const AP_Param::Info var_info[];

View File

@ -12,7 +12,7 @@ void ModeSteering::update()
// acceleration at full steering lock for this speed. That is V^2/R where R is the radius of turn.
// We get the radius of turn from half the STEER2SRV_P.
const float ground_speed = rover.ground_speed;
float max_g_force = ground_speed * ground_speed / rover.steerController.get_turn_radius();
float max_g_force = ground_speed * ground_speed / MAX(g2.turn_radius, 0.1f);
// constrain to user set TURN_MAX_G
max_g_force = constrain_float(max_g_force, 0.1f, g.turn_max_g * GRAVITY_MSS);