Plane: added AUTO_FBW_STEER option

this is an unusual option that gives FBWA flight control in AUTO
mode. It is being added to support use of APM in an aerial robotics
competition where students need to pilot the plane, but they still
need waypoint triggering of payloads
This commit is contained in:
Andrew Tridgell 2013-09-13 14:37:48 +10:00
parent 98a2ffd65c
commit cc6acac1dd
4 changed files with 213 additions and 188 deletions

View File

@ -1054,10 +1054,11 @@ static void update_GPS(void)
calc_gndspeed_undershoot();
}
static void update_flight_mode(void)
/*
main handling for AUTO mode
*/
static void handle_auto_mode(void)
{
if(control_mode == AUTO) {
switch(nav_command_ID) {
case MAV_CMD_NAV_TAKEOFF:
if (hold_course_cd == -1) {
@ -1082,7 +1083,6 @@ static void update_flight_mode(void)
// max throttle for takeoff
channel_throttle->servo_out = aparm.throttle_max;
break;
case MAV_CMD_NAV_LAND:
@ -1122,11 +1122,29 @@ static void update_flight_mode(void)
calc_throttle();
break;
}
}else{
}
/*
main flight mode dependent update code
*/
static void update_flight_mode(void)
{
enum FlightMode effective_mode = control_mode;
if (control_mode == AUTO && g.auto_fbw_steer) {
effective_mode = FLY_BY_WIRE_A;
}
if (effective_mode != AUTO) {
// hold_course is only used in takeoff and landing
hold_course_cd = -1;
}
switch (effective_mode)
{
case AUTO:
handle_auto_mode();
break;
switch(control_mode) {
case RTL:
case LOITER:
case GUIDED:
@ -1250,11 +1268,9 @@ static void update_flight_mode(void)
//roll: -13788.000, pitch: -13698.000, thr: 0.000, rud: -13742.000
case INITIALISING:
case AUTO:
// handled elsewhere
break;
}
}
}
static void update_navigation()

View File

@ -533,7 +533,7 @@ static bool suppress_throttle(void)
return false;
}
if (control_mode==AUTO && takeoff_complete == false && auto_takeoff_check()) {
if (control_mode==AUTO && !g.auto_fbw_steer && takeoff_complete == false && auto_takeoff_check()) {
// we're in auto takeoff
throttle_suppressed = false;
if (hold_course_cd != -1) {

View File

@ -92,6 +92,7 @@ public:
k_param_relay,
k_param_takeoff_throttle_delay,
k_param_skip_gyro_cal,
k_param_auto_fbw_steer,
// 110: Telemetry control
//
@ -281,6 +282,7 @@ public:
// skip gyro calibration
AP_Int8 skip_gyro_cal;
AP_Int8 auto_fbw_steer;
// Estimation
//

View File

@ -81,6 +81,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(skip_gyro_cal, "SKIP_GYRO_CAL", 0),
// @Param: AUTO_FBW_STEER
// @DisplayName: Use FBWA steering in AUTO
// @Description: When enabled this option gives FBWA navigation and steering in AUTO mode. This can be used to allow manual stabilised piloting with waypoint logic for triggering payloads. With this enabled the pilot has the same control over the plane as in FBWA mode, and the normal AUTO navigation is completely disabled. This option is not recommended for normal use.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(auto_fbw_steer, "AUTO_FBW_STEER", 0),
// @Param: TKOFF_THR_MINSPD
// @DisplayName: Takeoff throttle min speed
// @Description: Minimum GPS ground speed in m/s used by the speed check that un-suppresses throttle in auto-takeoff. This can be be used for catapult launches where you want the motor to engage only after the plane leaves the catapult, but it is preferable to use the TKOFF_THR_MINACC and TKOFF_THR_DELAY parameters for cvatapult launches due to the errors associated with GPS measurements. For hand launches with a pusher prop it is strongly advised that this parameter be set to a value no less than 4 m/s to provide additional protection against premature motor start. Note that the GPS velocity will lag the real velocity by about 0.5 seconds. The ground speed check is delayed by the TKOFF_THR_DELAY parameter.