Copter: make do_user_takeoff a member of Mode

This commit is contained in:
Peter Barker 2017-12-12 20:45:40 +11:00 committed by Randy Mackay
parent cb26ff64b3
commit cff1969a29
4 changed files with 11 additions and 10 deletions

View File

@ -923,7 +923,6 @@ private:
const char* get_frame_string(); const char* get_frame_string();
void allocate_motors(void); void allocate_motors(void);
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate);
void takeoff_timer_start(float alt_cm); void takeoff_timer_start(float alt_cm);
void takeoff_stop(); void takeoff_stop();
void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate); void takeoff_get_climb_rates(float& pilot_climb_rate, float& takeoff_climb_rate);

View File

@ -817,7 +817,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
float takeoff_alt = packet.param7 * 100; // Convert m to cm float takeoff_alt = packet.param7 * 100; // Convert m to cm
if(copter.do_user_takeoff(takeoff_alt, is_zero(packet.param3))) { if (copter.flightmode->do_user_takeoff(takeoff_alt, is_zero(packet.param3))) {
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
} else { } else {
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
@ -1109,7 +1109,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
} else if (copter.ap.land_complete) { } else if (copter.ap.land_complete) {
// if armed and landed, takeoff // if armed and landed, takeoff
if (copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) { if (copter.set_mode(LOITER, MODE_REASON_GCS_COMMAND)) {
copter.do_user_takeoff(packet.param1*100, true); copter.flightmode->do_user_takeoff(packet.param1*100, true);
} }
} else { } else {
// if flying, land // if flying, land

View File

@ -71,6 +71,8 @@ public:
}; };
static AutoYaw auto_yaw; static AutoYaw auto_yaw;
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate);
protected: protected:
virtual bool init(bool ignore_checks) = 0; virtual bool init(bool ignore_checks) = 0;

View File

@ -6,22 +6,22 @@
// the pos_control target is then slowly increased until time_ms expires // the pos_control target is then slowly increased until time_ms expires
// initiate user takeoff - called when MAVLink TAKEOFF command is received // initiate user takeoff - called when MAVLink TAKEOFF command is received
bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate) bool Copter::Mode::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
{ {
if (motors->armed() && ap.land_complete && flightmode->has_user_takeoff(must_navigate) && takeoff_alt_cm > current_loc.alt) { if (copter.motors->armed() && ap.land_complete && has_user_takeoff(must_navigate) && takeoff_alt_cm > copter.current_loc.alt) {
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
// Helicopters should return false if MAVlink takeoff command is received while the rotor is not spinning // Helicopters should return false if MAVlink takeoff command is received while the rotor is not spinning
if (!motors->rotor_runup_complete()) { if (!copter.motors->rotor_runup_complete()) {
return false; return false;
} }
#endif #endif
switch(control_mode) { switch(copter.control_mode) {
#if MODE_GUIDED_ENABLED == ENABLED #if MODE_GUIDED_ENABLED == ENABLED
case GUIDED: case GUIDED:
if (mode_guided.takeoff_start(takeoff_alt_cm)) { if (copter.mode_guided.takeoff_start(takeoff_alt_cm)) {
set_auto_armed(true); copter.set_auto_armed(true);
return true; return true;
} }
return false; return false;
@ -31,7 +31,7 @@ bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
case ALT_HOLD: case ALT_HOLD:
case SPORT: case SPORT:
case FLOWHOLD: case FLOWHOLD:
set_auto_armed(true); copter.set_auto_armed(true);
takeoff_timer_start(takeoff_alt_cm); takeoff_timer_start(takeoff_alt_cm);
return true; return true;
default: default: