mirror of https://github.com/ArduPilot/ardupilot
Plane: added support for DO_AUTOTUNE_ENABLE
This commit is contained in:
parent
d5c5400e76
commit
76c0293a85
|
@ -1347,6 +1347,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
|
// param1 : enable/disable
|
||||||
|
plane.autotune_enable(packet.param1);
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -751,6 +751,7 @@ private:
|
||||||
void reset_control_switch();
|
void reset_control_switch();
|
||||||
void autotune_start(void);
|
void autotune_start(void);
|
||||||
void autotune_restore(void);
|
void autotune_restore(void);
|
||||||
|
void autotune_enable(bool enable);
|
||||||
bool fly_inverted(void);
|
bool fly_inverted(void);
|
||||||
void failsafe_short_on_event(enum failsafe_state fstype);
|
void failsafe_short_on_event(enum failsafe_state fstype);
|
||||||
void failsafe_long_on_event(enum failsafe_state fstype);
|
void failsafe_long_on_event(enum failsafe_state fstype);
|
||||||
|
|
|
@ -145,6 +145,9 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
|
autotune_enable(cmd.p1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
|
@ -267,6 +270,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
||||||
case MAV_CMD_DO_INVERTED_FLIGHT:
|
case MAV_CMD_DO_INVERTED_FLIGHT:
|
||||||
case MAV_CMD_DO_LAND_START:
|
case MAV_CMD_DO_LAND_START:
|
||||||
case MAV_CMD_DO_FENCE_ENABLE:
|
case MAV_CMD_DO_FENCE_ENABLE:
|
||||||
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
return true;
|
return true;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -146,6 +146,18 @@ void Plane::autotune_restore(void)
|
||||||
pitchController.autotune_restore();
|
pitchController.autotune_restore();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
enable/disable autotune for AUTO modes
|
||||||
|
*/
|
||||||
|
void Plane::autotune_enable(bool enable)
|
||||||
|
{
|
||||||
|
if (enable) {
|
||||||
|
autotune_start();
|
||||||
|
} else {
|
||||||
|
autotune_restore();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
are we flying inverted?
|
are we flying inverted?
|
||||||
*/
|
*/
|
||||||
|
|
Loading…
Reference in New Issue