mirror of https://github.com/ArduPilot/ardupilot
Rover: tweaked parameters and added SPEED_TURN_GAIN and SPEED_TURN_DIST
This commit is contained in:
parent
52800e52b9
commit
bf6198be40
|
@ -66,6 +66,8 @@ public:
|
|||
k_param_crosstrack_gain = 150,
|
||||
k_param_crosstrack_entry_angle,
|
||||
k_param_speed_cruise,
|
||||
k_param_speed_turn_gain,
|
||||
k_param_speed_turn_dist,
|
||||
k_param_ch7_option,
|
||||
|
||||
//
|
||||
|
@ -169,6 +171,8 @@ public:
|
|||
AP_Float crosstrack_gain;
|
||||
AP_Int16 crosstrack_entry_angle;
|
||||
AP_Float speed_cruise;
|
||||
AP_Int8 speed_turn_gain;
|
||||
AP_Float speed_turn_dist;
|
||||
AP_Int8 ch7_option;
|
||||
|
||||
// RC channels
|
||||
|
|
|
@ -58,7 +58,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
|
||||
// @Param: SERIAL0_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @DisplayName: USB Console Baud Rate
|
||||
// @Description: The baud rate used on the first serial port
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200
|
||||
// @User: Standard
|
||||
|
@ -136,7 +136,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
GSCALAR(crosstrack_entry_angle, "XTRK_ANGLE_CD", XTRACK_ENTRY_ANGLE_CENTIDEGREE),
|
||||
|
||||
// @Param: CRUISE_SPEED
|
||||
// @DisplayName: Target speed in auto modes
|
||||
// @DisplayName: Target cruise speed in auto modes
|
||||
// @Description: The target speed in auto missions.
|
||||
// @Units: m/s
|
||||
// @Range: 0 100
|
||||
|
@ -144,6 +144,24 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
GSCALAR(speed_cruise, "CRUISE_SPEED", 5),
|
||||
|
||||
// @Param: SPEED_TURN_GAIN
|
||||
// @DisplayName: Target speed reduction while turning
|
||||
// @Description: The percentage to reduce the throttle while turning. If this is 100% then the target speed is not reduced while turning. If this is 50% then the target speed is reduced in proportion to the turn rate, with a reduction of 50% when the steering is maximally deflected.
|
||||
// @Units: percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(speed_turn_gain, "SPEED_TURN_GAIN", 50),
|
||||
|
||||
// @Param: SPEED_TURN_DIST
|
||||
// @DisplayName: Distance to turn to start reducing speed
|
||||
// @Description: The distance to the next turn at which the rover reduces its target speed by the SPEED_TURN_GAIN
|
||||
// @Units: meters
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(speed_turn_dist, "SPEED_TURN_DIST", 2.0f),
|
||||
|
||||
// @Param: CH7_OPTION
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: What to do use channel 7 for
|
||||
|
@ -171,7 +189,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
|
||||
// @Param: THR_MAX
|
||||
// @DisplayName: Maximum Throttle
|
||||
// @Description: The maximum throttle setting to which the autopilot will apply.
|
||||
// @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: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
|
@ -180,7 +198,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
|
||||
// @Param: CRUISE_THROTTLE
|
||||
// @DisplayName: Base throttle percentage in auto
|
||||
// @Description: The base throttle percentage to use in auto mode
|
||||
// @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.
|
||||
// @Units: Percent
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
|
|
|
@ -383,7 +383,7 @@
|
|||
# define THROTTLE_CRUISE 45
|
||||
#endif
|
||||
#ifndef THROTTLE_MAX
|
||||
# define THROTTLE_MAX 75
|
||||
# define THROTTLE_MAX 100
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -411,7 +411,7 @@
|
|||
# define XTRACK_GAIN 1 // deg/m
|
||||
#endif
|
||||
#ifndef XTRACK_ENTRY_ANGLE
|
||||
# define XTRACK_ENTRY_ANGLE 20 // deg
|
||||
# define XTRACK_ENTRY_ANGLE 50 // deg
|
||||
#endif
|
||||
# define XTRACK_GAIN_SCALED XTRACK_GAIN*100
|
||||
# define XTRACK_ENTRY_ANGLE_CENTIDEGREE XTRACK_ENTRY_ANGLE*100
|
||||
|
|
Loading…
Reference in New Issue