mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: remove skid_steer_out parameter
This commit is contained in:
parent
0017485ee7
commit
c865972e9c
@ -211,13 +211,6 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
|
||||
|
||||
// @Param: SKID_STEER_OUT
|
||||
// @DisplayName: Skid steering output
|
||||
// @Description: Set this to 1 for skid steering controlled rovers (tank track style). When enabled, servo1 is used for the left track control, servo3 is used for right track control
|
||||
// @Values: 0:Disabled, 1:SkidSteeringOutput
|
||||
// @User: Standard
|
||||
GSCALAR(skid_steer_out, "SKID_STEER_OUT", 0),
|
||||
|
||||
// @Param: SKID_STEER_IN
|
||||
// @DisplayName: Skid steering input
|
||||
// @Description: Set this to 1 for skid steering input rovers (tank track style in RC controller). When enabled, servo1 is used for the left track control, servo3 is used for right track control
|
||||
|
@ -129,7 +129,7 @@ public:
|
||||
k_param_throttle_slewrate,
|
||||
k_param_throttle_reduction,
|
||||
k_param_skid_steer_in,
|
||||
k_param_skid_steer_out,
|
||||
k_param_skid_steer_out_old,
|
||||
|
||||
// failsafe control
|
||||
k_param_fs_action = 180,
|
||||
@ -249,7 +249,6 @@ public:
|
||||
AP_Int8 throttle_cruise;
|
||||
AP_Int8 throttle_slewrate;
|
||||
AP_Int8 skid_steer_in;
|
||||
AP_Int8 skid_steer_out;
|
||||
|
||||
// failsafe control
|
||||
AP_Int8 fs_action;
|
||||
|
Loading…
Reference in New Issue
Block a user