Copter: play various tones
This commit is contained in:
parent
3dfcdde6be
commit
f045c75bfe
@ -278,6 +278,8 @@ static bool verify_command(const AP_Mission::Mission_Command& cmd)
|
||||
// exit_mission - function that is called once the mission completes
|
||||
static void exit_mission()
|
||||
{
|
||||
// play a tone
|
||||
AP_Notify::events.mission_complete = 1;
|
||||
// if we are not on the ground switch to loiter or land
|
||||
if(!ap.land_complete) {
|
||||
// try to enter loiter but if that fails land
|
||||
@ -632,6 +634,9 @@ static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
||||
return false;
|
||||
}
|
||||
|
||||
// play a tone
|
||||
AP_Notify::events.waypoint_complete = 1;
|
||||
|
||||
// start timer if necessary
|
||||
if(loiter_time == 0) {
|
||||
loiter_time = millis();
|
||||
|
@ -653,6 +653,7 @@ static void autotune_attitude_control()
|
||||
if (autotune_state.axis == AUTOTUNE_AXIS_ROLL) {
|
||||
tune_roll_sp = tune_roll_sp * AUTOTUNE_SP_BACKOFF;
|
||||
autotune_state.axis = AUTOTUNE_AXIS_PITCH;
|
||||
AP_Notify::events.autotune_next_axis = 1;
|
||||
}else{
|
||||
tune_pitch_sp = tune_pitch_sp * AUTOTUNE_SP_BACKOFF;
|
||||
tune_roll_sp = min(tune_roll_sp, tune_pitch_sp);
|
||||
@ -662,6 +663,9 @@ static void autotune_attitude_control()
|
||||
autotune_state.mode = AUTOTUNE_MODE_SUCCESS;
|
||||
autotune_update_gcs(AUTOTUNE_MESSAGE_SUCCESS);
|
||||
Log_Write_Event(DATA_AUTOTUNE_SUCCESS);
|
||||
|
||||
// play a tone
|
||||
AP_Notify::events.autotune_complete = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -685,6 +689,9 @@ static void autotune_failed()
|
||||
attitude_control.limit_angle_to_rate_request(true);
|
||||
// log failure
|
||||
Log_Write_Event(DATA_AUTOTUNE_FAILED);
|
||||
|
||||
// play a tone
|
||||
AP_Notify::events.autotune_failed = 1;
|
||||
}
|
||||
|
||||
// autotune_backup_gains_and_initialise - store current gains as originals
|
||||
|
@ -26,11 +26,12 @@ static void read_control_switch()
|
||||
bool failsafe_disengaged = !failsafe.radio && failsafe.radio_counter == 0;
|
||||
|
||||
if (control_switch_changed && sufficient_time_elapsed && failsafe_disengaged) {
|
||||
// set the debounced switch position
|
||||
control_switch_state.debounced_switch_position = switch_position;
|
||||
|
||||
// set flight mode and simple mode setting
|
||||
if (set_mode(flight_modes[switch_position])) {
|
||||
// play a tone
|
||||
if (control_switch_state.debounced_switch_position != -1) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
}
|
||||
|
||||
if(g.ch7_option != AUX_SWITCH_SIMPLE_MODE && g.ch8_option != AUX_SWITCH_SIMPLE_MODE && g.ch7_option != AUX_SWITCH_SUPERSIMPLE_MODE && g.ch8_option != AUX_SWITCH_SUPERSIMPLE_MODE) {
|
||||
// set Simple mode using stored paramters from Mission planner
|
||||
@ -41,6 +42,12 @@ static void read_control_switch()
|
||||
set_simple_mode(BIT_IS_SET(g.simple_modes, switch_position));
|
||||
}
|
||||
}
|
||||
|
||||
// set the debounced switch position
|
||||
control_switch_state.debounced_switch_position = switch_position;
|
||||
}
|
||||
else if (control_switch_state.last_switch_position != -1) {
|
||||
AP_Notify::events.user_mode_change_failed = 1;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user