mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Plane: fixed X accel triggering of auto
This commit is contained in:
parent
a6b21443c4
commit
1d983b3f2e
@ -101,6 +101,7 @@ static Parameters g;
|
|||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// prototypes
|
// prototypes
|
||||||
static void update_events(void);
|
static void update_events(void);
|
||||||
|
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -392,15 +392,21 @@ static bool auto_takeoff_check(void)
|
|||||||
// we haven't reached the minimum ground speed
|
// we haven't reached the minimum ground speed
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (g.takeoff_throttle_min_accel > 0.0f &&
|
|
||||||
(ins.get_accel().x < g.takeoff_throttle_min_accel) &&
|
if (g.takeoff_throttle_min_accel > 0.0f) {
|
||||||
ahrs.pitch_sensor > -3000 && ahrs.pitch_sensor < 4500 &&
|
float xaccel = ins.get_accel().x;
|
||||||
abs(ahrs.roll_sensor) < 3000) {
|
if (ahrs.pitch_sensor > -3000 &&
|
||||||
// we haven't reached the minimum acceleration or we are not
|
ahrs.pitch_sensor < 4500 &&
|
||||||
// anywhere near flat. Thanks to Chris Miser for this
|
abs(ahrs.roll_sensor) < 3000 &&
|
||||||
// suggestion
|
xaccel >= g.takeoff_throttle_min_accel) {
|
||||||
|
// trigger with minimum acceleration when flat
|
||||||
|
// Thanks to Chris Miser for this suggestion
|
||||||
|
gcs_send_text_fmt(PSTR("Triggered AUTO xaccel=%.1f"), xaccel);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// we're good for takeoff
|
// we're good for takeoff
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -9,9 +9,6 @@ static bool mavlink_active;
|
|||||||
// check if a message will fit in the payload space available
|
// check if a message will fit in the payload space available
|
||||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_ ## id ## _LEN) return false
|
||||||
|
|
||||||
// prototype this for use inside the GCS class
|
|
||||||
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* !!NOTE!!
|
* !!NOTE!!
|
||||||
*
|
*
|
||||||
|
Loading…
Reference in New Issue
Block a user