Browse Source

Copter: pre-arm check for gps hdop < 2

master
Randy Mackay 12 years ago
parent
commit
d000967a76
  1. 4
      ArduCopter/Parameters.h
  2. 7
      ArduCopter/Parameters.pde
  3. 3
      ArduCopter/config.h
  4. 4
      ArduCopter/motors.pde

4
ArduCopter/Parameters.h

@ -89,7 +89,8 @@ public: @@ -89,7 +89,8 @@ public:
k_param_ch8_option,
k_param_arming_check_enabled,
k_param_sprayer,
k_param_angle_max, // 34
k_param_angle_max,
k_param_gps_hdop_good, // 35
// 65: AP_Limits Library
k_param_limits = 65, // deprecated - remove
@ -287,6 +288,7 @@ public: @@ -287,6 +288,7 @@ public:
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
AP_Int8 failsafe_gps_enabled; // gps failsafe enabled
AP_Int8 failsafe_gcs; // ground station failsafe behavior
AP_Int16 gps_hdop_good; // GPS Hdop value below which represent a good position
AP_Int8 compass_enabled;
AP_Int8 optflow_enabled;

7
ArduCopter/Parameters.pde

@ -113,6 +113,13 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -113,6 +113,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),
// @Param: GPS_HDOP_GOOD
// @DisplayName: GPS Hdop Good
// @Description: GPS Hdop value below which represent a good position. Used for pre-arm checks
// @Range: 100 900
// @User: Advanced
GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),
// @Param: VOLT_DIVIDER
// @DisplayName: Voltage Divider
// @Description: Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_DIVIDER). For the 3DR Power brick, this should be set to 10.1. For the PX4 using the PX4IO power supply this should be set to 1.

3
ArduCopter/config.h

@ -394,6 +394,9 @@ @@ -394,6 +394,9 @@
#ifndef FAILSAFE_GPS_TIMEOUT_MS
# define FAILSAFE_GPS_TIMEOUT_MS 5000 // gps failsafe triggers after 5 seconds with no GPS
#endif
#ifndef GPS_HDOP_GOOD_DEFAULT
# define GPS_HDOP_GOOD_DEFAULT 200 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled
#endif
// GCS failsafe
#ifndef FS_GCS

4
ArduCopter/motors.pde

@ -293,9 +293,9 @@ static void pre_arm_checks(bool display_failure) @@ -293,9 +293,9 @@ static void pre_arm_checks(bool display_failure)
#if AC_FENCE == ENABLED
// check fence is initialised
if(!fence.pre_arm_check()) {
if(!fence.pre_arm_check() || (fence.enabled() && g_gps->hdop > g.gps_hdop_good)) {
if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: No GPS Lock"));
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Bad GPS Pos"));
}
return;
}

Loading…
Cancel
Save