Browse Source

Rover: auto-reversed moved to mode

mission-4.1.18
Randy Mackay 8 years ago
parent
commit
30852d4713
  1. 2
      APMrover2/APMrover2.cpp
  2. 3
      APMrover2/Rover.h
  3. 9
      APMrover2/commands_logic.cpp
  4. 4
      APMrover2/system.cpp

2
APMrover2/APMrover2.cpp

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

3
APMrover2/Rover.h

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

9
APMrover2/commands_logic.cpp

@ -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) void Rover::do_set_reverse(const AP_Mission::Mission_Command& cmd)
{ {
if (cmd.p1 == 1) { mode_auto.set_reversed(cmd.p1 == 1);
in_auto_reverse = true; set_reverse(cmd.p1 == 1);
set_reverse(true);
} else {
in_auto_reverse = false;
set_reverse(false);
}
} }

4
APMrover2/system.cpp

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

Loading…
Cancel
Save