Browse Source

Rover: added HOLD mode

used when RTL completes
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
caf5e5b7c5
  1. 9
      APMrover2/APMrover2.pde
  2. 5
      APMrover2/GCS_Mavlink.pde
  3. 12
      APMrover2/Parameters.pde
  4. 4
      APMrover2/commands_logic.pde
  5. 1
      APMrover2/defines.h
  6. 1
      APMrover2/events.pde
  7. 1
      APMrover2/setup.pde
  8. 4
      APMrover2/system.pde

9
APMrover2/APMrover2.pde

@ -863,6 +863,12 @@ static void update_current_mode(void)
g.channel_steer.servo_out = g.channel_steer.pwm_to_angle(); g.channel_steer.servo_out = g.channel_steer.pwm_to_angle();
break; break;
case HOLD:
// hold position - stop motors and center steering
g.channel_throttle.servo_out = 0;
g.channel_steer.servo_out = 0;
break;
case INITIALISING: case INITIALISING:
break; break;
} }
@ -872,6 +878,7 @@ static void update_navigation()
{ {
switch (control_mode) { switch (control_mode) {
case MANUAL: case MANUAL:
case HOLD:
case LEARNING: case LEARNING:
case STEERING: case STEERING:
case INITIALISING: case INITIALISING:
@ -888,7 +895,7 @@ static void update_navigation()
calc_bearing_error(); calc_bearing_error();
if (verify_RTL()) { if (verify_RTL()) {
g.channel_throttle.servo_out = g.throttle_min.get(); g.channel_throttle.servo_out = g.throttle_min.get();
set_mode(MANUAL); set_mode(HOLD);
} }
break; break;
} }

5
APMrover2/GCS_Mavlink.pde

@ -54,6 +54,9 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
case INITIALISING: case INITIALISING:
system_status = MAV_STATE_CALIBRATING; system_status = MAV_STATE_CALIBRATING;
break; break;
case HOLD:
system_status = 0;
break;
} }
#if ENABLE_STICK_MIXING==ENABLED #if ENABLE_STICK_MIXING==ENABLED
@ -132,6 +135,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
switch (control_mode) { switch (control_mode) {
case MANUAL: case MANUAL:
case HOLD:
break; break;
case LEARNING: case LEARNING:
@ -1074,6 +1078,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} }
switch (packet.custom_mode) { switch (packet.custom_mode) {
case MANUAL: case MANUAL:
case HOLD:
case LEARNING: case LEARNING:
case STEERING: case STEERING:
case AUTO: case AUTO:

12
APMrover2/Parameters.pde

@ -307,7 +307,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: MODE1 // @Param: MODE1
// @DisplayName: Mode1 // @DisplayName: Mode1
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049) // @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
GSCALAR(mode1, "MODE1", MODE_1), GSCALAR(mode1, "MODE1", MODE_1),
@ -315,35 +315,35 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: MODE2 // @Param: MODE2
// @DisplayName: Mode2 // @DisplayName: Mode2
// @Description: Driving mode for switch position 2 (1231 to 1360) // @Description: Driving mode for switch position 2 (1231 to 1360)
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
GSCALAR(mode2, "MODE2", MODE_2), GSCALAR(mode2, "MODE2", MODE_2),
// @Param: MODE3 // @Param: MODE3
// @DisplayName: Mode3 // @DisplayName: Mode3
// @Description: Driving mode for switch position 3 (1361 to 1490) // @Description: Driving mode for switch position 3 (1361 to 1490)
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
GSCALAR(mode3, "MODE3", MODE_3), GSCALAR(mode3, "MODE3", MODE_3),
// @Param: MODE4 // @Param: MODE4
// @DisplayName: Mode4 // @DisplayName: Mode4
// @Description: Driving mode for switch position 4 (1491 to 1620) // @Description: Driving mode for switch position 4 (1491 to 1620)
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
GSCALAR(mode4, "MODE4", MODE_4), GSCALAR(mode4, "MODE4", MODE_4),
// @Param: MODE5 // @Param: MODE5
// @DisplayName: Mode5 // @DisplayName: Mode5
// @Description: Driving mode for switch position 5 (1621 to 1749) // @Description: Driving mode for switch position 5 (1621 to 1749)
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
GSCALAR(mode5, "MODE5", MODE_5), GSCALAR(mode5, "MODE5", MODE_5),
// @Param: MODE6 // @Param: MODE6
// @DisplayName: Mode6 // @DisplayName: Mode6
// @Description: Driving mode for switch position 6 (1750 to 2049) // @Description: Driving mode for switch position 6 (1750 to 2049)
// @Values: 0:Manual,2:LEARNING,3:STEERING,10:Auto,11:RTL,15:Guided // @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
// @User: Standard // @User: Standard
GSCALAR(mode6, "MODE6", MODE_6), GSCALAR(mode6, "MODE6", MODE_6),

4
APMrover2/commands_logic.pde

@ -109,8 +109,8 @@ static void handle_process_do_command()
static void handle_no_commands() static void handle_no_commands()
{ {
gcs_send_text_fmt(PSTR("No commands - setting MANUAL")); gcs_send_text_fmt(PSTR("No commands - setting HOLD"));
set_mode(MANUAL); set_mode(HOLD);
} }
/********************************************************************************/ /********************************************************************************/

1
APMrover2/defines.h

@ -66,6 +66,7 @@ enum mode {
MANUAL=0, MANUAL=0,
LEARNING=2, LEARNING=2,
STEERING=3, STEERING=3,
HOLD=4,
AUTO=10, AUTO=10,
RTL=11, RTL=11,
GUIDED=15, GUIDED=15,

1
APMrover2/events.pde

@ -21,6 +21,7 @@ static void failsafe_long_on_event(int fstype)
break; break;
case RTL: case RTL:
case HOLD:
default: default:
break; break;
} }

1
APMrover2/setup.pde

@ -338,6 +338,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
while ( while (
mode != MANUAL && mode != MANUAL &&
mode != HOLD &&
mode != LEARNING && mode != LEARNING &&
mode != STEERING && mode != STEERING &&
mode != AUTO && mode != AUTO &&

4
APMrover2/system.pde

@ -314,6 +314,7 @@ static void set_mode(enum mode mode)
switch(control_mode) switch(control_mode)
{ {
case MANUAL: case MANUAL:
case HOLD:
case LEARNING: case LEARNING:
case STEERING: case STEERING:
break; break;
@ -495,6 +496,9 @@ print_mode(uint8_t mode)
case MANUAL: case MANUAL:
cliSerial->println_P(PSTR("Manual")); cliSerial->println_P(PSTR("Manual"));
break; break;
case HOLD:
cliSerial->println_P(PSTR("HOLD"));
break;
case LEARNING: case LEARNING:
cliSerial->println_P(PSTR("Learning")); cliSerial->println_P(PSTR("Learning"));
break; break;

Loading…
Cancel
Save