Rover: auto-reversed moved to mode

This commit is contained in:
Randy Mackay 2017-08-03 15:20:34 +09:00
parent 4f5e82f406
commit 30852d4713
4 changed files with 2 additions and 16 deletions

View File

@ -104,8 +104,6 @@ void Rover::setup()
// load the default values of variables listed in var_info[]
AP_Param::setup_sketch_defaults();
in_auto_reverse = false;
init_ardupilot();
// initialise the main loop scheduler

View File

@ -351,9 +351,6 @@ private:
// set if we are driving backwards
bool in_reverse;
// set if the users asks for auto reverse
bool in_auto_reverse;
// true if pivoting (set by use_pivot_steering)
bool pivot_steering_active;

View File

@ -423,11 +423,6 @@ void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1) {
in_auto_reverse = true;
set_reverse(true);
} else {
in_auto_reverse = false;
set_reverse(false);
}
mode_auto.set_reversed(cmd.p1 == 1);
set_reverse(cmd.p1 == 1);
}

View File

@ -276,10 +276,6 @@ void Rover::set_reverse(bool reverse)
if (in_reverse == reverse) {
return;
}
g.pidSpeedThrottle.reset_I();
steerController.reset_I();
nav_controller->set_reverse(reverse);
steerController.set_reverse(reverse);
in_reverse = reverse;
}