Plane: implement VTOL flight stage

This commit is contained in:
Andrew Tridgell 2016-01-01 17:36:41 +11:00
parent b3bd83b1c6
commit 7afa2a493d
3 changed files with 24 additions and 2 deletions

View File

@ -824,6 +824,7 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
case AP_SpdHgtControl::FLIGHT_LAND_FINAL:
case AP_SpdHgtControl::FLIGHT_NORMAL:
case AP_SpdHgtControl::FLIGHT_VTOL:
case AP_SpdHgtControl::FLIGHT_TAKEOFF:
break;
}
@ -866,7 +867,9 @@ void Plane::update_flight_stage(void)
// Update the speed & height controller states
if (auto_throttle_mode && !throttle_suppressed) {
if (control_mode==AUTO) {
if (auto_state.takeoff_complete == false) {
if (auto_state.vtol_mode) {
set_flight_stage(AP_SpdHgtControl::FLIGHT_VTOL);
} else if (auto_state.takeoff_complete == false) {
set_flight_stage(AP_SpdHgtControl::FLIGHT_TAKEOFF);
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
@ -887,10 +890,15 @@ void Plane::update_flight_stage(void)
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL);
}
}
} else if (quadplane.in_assisted_flight()) {
set_flight_stage(AP_SpdHgtControl::FLIGHT_VTOL);
} else {
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL);
}
} else if (control_mode == QSTABILIZE ||
control_mode == QHOVER ||
control_mode == QLOITER) {
set_flight_stage(AP_SpdHgtControl::FLIGHT_VTOL);
} else {
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL);
}

View File

@ -83,6 +83,10 @@ void Plane::update_is_flying_5Hz(void)
}
break;
case AP_SpdHgtControl::FLIGHT_VTOL:
// TODO: detect ground impacts
break;
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
if (fabsf(auto_state.sink_rate) > 0.2f) {
is_flying_bool = true;
@ -198,6 +202,11 @@ void Plane::crash_detection_update(void)
// TODO: handle auto missions without NAV_TAKEOFF mission cmd
break;
case AP_SpdHgtControl::FLIGHT_VTOL:
// we need a totally new method for this
crashed = false;
break;
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH:
crashed = true;
// when altitude gets low, we automatically progress to FLIGHT_LAND_FINAL

View File

@ -35,6 +35,11 @@ public:
return initialised;
}
// is quadplane assisting?
bool in_assisted_flight(void) const {
return available() && assisted_flight;
}
bool handle_do_vtol_transition(const mavlink_command_long_t &packet);
private: