Browse Source

Copter: add land_complete_maybe flag

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
b9977a1115
  1. 15
      ArduCopter/AP_State.pde
  2. 1
      ArduCopter/ArduCopter.pde
  3. 10
      ArduCopter/control_land.pde
  4. 1
      ArduCopter/defines.h
  5. 1
      ArduCopter/motors.pde
  6. 1
      ArduCopter/system.pde

15
ArduCopter/AP_State.pde

@ -110,6 +110,21 @@ void set_land_complete(bool b) @@ -110,6 +110,21 @@ void set_land_complete(bool b)
// ---------------------------------------------
// set land complete maybe flag
void set_land_complete_maybe(bool b)
{
// if no change, exit immediately
if (ap.land_complete_maybe == b)
return;
if (b) {
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
}
ap.land_complete_maybe = b;
}
// ---------------------------------------------
void set_pre_arm_check(bool b)
{
if(ap.pre_arm_check != b) {

1
ArduCopter/ArduCopter.pde

@ -389,6 +389,7 @@ static union { @@ -389,6 +389,7 @@ static union {
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 18 // true if we may have landed (less strict version of land_complete)
};
uint32_t value;
} ap;

10
ArduCopter/control_land.pde

@ -1,7 +1,7 @@ @@ -1,7 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// counter to verify landings
static uint16_t land_detector;
static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed
static bool land_with_gps;
static uint32_t land_start_time;
@ -192,9 +192,10 @@ static float get_throttle_land() @@ -192,9 +192,10 @@ static float get_throttle_land()
}
}
// land_maybe_complete - return true if we may have landed (used to reset loiter targets during landing)
static bool land_maybe_complete()
{
return (ap.land_complete || land_detector > LAND_DETECTOR_MAYBE_TRIGGER);
return (ap.land_complete || ap.land_complete_maybe);
}
// update_land_detector - checks if we have landed and updates the ap.land_complete flag
@ -210,7 +211,7 @@ static void update_land_detector() @@ -210,7 +211,7 @@ static void update_land_detector()
land_detector++;
}else{
set_land_complete(true);
land_detector = 0;
land_detector = LAND_DETECTOR_TRIGGER;
}
}
} else {
@ -221,6 +222,9 @@ static void update_land_detector() @@ -221,6 +222,9 @@ static void update_land_detector()
set_land_complete(false);
}
}
// set land maybe flag
set_land_complete_maybe(land_detector >= LAND_DETECTOR_MAYBE_TRIGGER);
}
// land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch

1
ArduCopter/defines.h

@ -267,6 +267,7 @@ enum FlipState { @@ -267,6 +267,7 @@ enum FlipState {
#define DATA_DISARMED 11
#define DATA_AUTO_ARMED 15
#define DATA_TAKEOFF 16
#define DATA_LAND_COMPLETE_MAYBE 17
#define DATA_LAND_COMPLETE 18
#define DATA_NOT_LANDED 28
#define DATA_LOST_GPS 19

1
ArduCopter/motors.pde

@ -615,6 +615,7 @@ static void init_disarm_motors() @@ -615,6 +615,7 @@ static void init_disarm_motors()
// we are not in the air
set_land_complete(true);
set_land_complete_maybe(true);
// reset the mission
mission.reset();

1
ArduCopter/system.pde

@ -322,6 +322,7 @@ static void startup_ground(bool force_gyro_cal) @@ -322,6 +322,7 @@ static void startup_ground(bool force_gyro_cal)
// set landed flag
set_land_complete(true);
set_land_complete_maybe(true);
}
// returns true if the GPS is ok and home position is set

Loading…
Cancel
Save