mirror of https://github.com/ArduPilot/ardupilot
Copter: Change to Boolean value
This commit is contained in:
parent
01eb0fd26d
commit
f3914dfc16
|
@ -48,14 +48,14 @@ bool ModeAutorotate::init(bool ignore_checks)
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Autorotation initiated");
|
gcs().send_text(MAV_SEVERITY_INFO, "Autorotation initiated");
|
||||||
|
|
||||||
// Set all intial flags to on
|
// Set all intial flags to on
|
||||||
_flags.entry_initial = 1;
|
_flags.entry_initial = true;
|
||||||
_flags.ss_glide_initial = 1;
|
_flags.ss_glide_initial = true;
|
||||||
_flags.flare_initial = 1;
|
_flags.flare_initial = true;
|
||||||
_flags.touch_down_initial = 1;
|
_flags.touch_down_initial = true;
|
||||||
_flags.level_initial = 1;
|
_flags.level_initial = true;
|
||||||
_flags.break_initial = 1;
|
_flags.break_initial = true;
|
||||||
_flags.straight_ahead_initial = 1;
|
_flags.straight_ahead_initial = true;
|
||||||
_flags.bail_out_initial = 1;
|
_flags.bail_out_initial = true;
|
||||||
_msg_flags.bad_rpm = true;
|
_msg_flags.bad_rpm = true;
|
||||||
|
|
||||||
// Setting default starting switches
|
// Setting default starting switches
|
||||||
|
@ -114,7 +114,7 @@ void ModeAutorotate::run()
|
||||||
case Autorotation_Phase::ENTRY:
|
case Autorotation_Phase::ENTRY:
|
||||||
{
|
{
|
||||||
// Entry phase functions to be run only once
|
// Entry phase functions to be run only once
|
||||||
if (_flags.entry_initial == 1) {
|
if (_flags.entry_initial == true) {
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Entry Phase");
|
gcs().send_text(MAV_SEVERITY_INFO, "Entry Phase");
|
||||||
|
@ -130,7 +130,7 @@ void ModeAutorotate::run()
|
||||||
g2.arot.set_desired_fwd_speed();
|
g2.arot.set_desired_fwd_speed();
|
||||||
|
|
||||||
// Prevent running the initial entry functions again
|
// Prevent running the initial entry functions again
|
||||||
_flags.entry_initial = 0;
|
_flags.entry_initial = false;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -160,7 +160,7 @@ void ModeAutorotate::run()
|
||||||
case Autorotation_Phase::SS_GLIDE:
|
case Autorotation_Phase::SS_GLIDE:
|
||||||
{
|
{
|
||||||
// Steady state glide functions to be run only once
|
// Steady state glide functions to be run only once
|
||||||
if (_flags.ss_glide_initial == 1) {
|
if (_flags.ss_glide_initial == true) {
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "SS Glide Phase");
|
gcs().send_text(MAV_SEVERITY_INFO, "SS Glide Phase");
|
||||||
|
@ -177,7 +177,7 @@ void ModeAutorotate::run()
|
||||||
g2.arot.set_target_head_speed(_target_head_speed);
|
g2.arot.set_target_head_speed(_target_head_speed);
|
||||||
|
|
||||||
// Prevent running the initial glide functions again
|
// Prevent running the initial glide functions again
|
||||||
_flags.ss_glide_initial = 0;
|
_flags.ss_glide_initial = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Run airspeed/attitude controller
|
// Run airspeed/attitude controller
|
||||||
|
@ -202,7 +202,7 @@ void ModeAutorotate::run()
|
||||||
|
|
||||||
case Autorotation_Phase::BAIL_OUT:
|
case Autorotation_Phase::BAIL_OUT:
|
||||||
{
|
{
|
||||||
if (_flags.bail_out_initial == 1) {
|
if (_flags.bail_out_initial == true) {
|
||||||
// Functions and settings to be done once are done here.
|
// Functions and settings to be done once are done here.
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
@ -243,7 +243,7 @@ void ModeAutorotate::run()
|
||||||
|
|
||||||
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
||||||
|
|
||||||
_flags.bail_out_initial = 0;
|
_flags.bail_out_initial = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((now - _bail_time_start_ms)/1000.0f >= BAILOUT_MOTOR_RAMP_TIME) {
|
if ((now - _bail_time_start_ms)/1000.0f >= BAILOUT_MOTOR_RAMP_TIME) {
|
||||||
|
|
|
@ -890,9 +890,9 @@ void ToyMode::blink_update(void)
|
||||||
// let the TX know we are recording video
|
// let the TX know we are recording video
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
if (now - last_video_ms < 1000) {
|
if (now - last_video_ms < 1000) {
|
||||||
AP_Notify::flags.video_recording = 1;
|
AP_Notify::flags.video_recording = true;
|
||||||
} else {
|
} else {
|
||||||
AP_Notify::flags.video_recording = 0;
|
AP_Notify::flags.video_recording = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (red_blink_count > 0 && green_blink_count > 0) {
|
if (red_blink_count > 0 && green_blink_count > 0) {
|
||||||
|
@ -954,7 +954,7 @@ void ToyMode::handle_message(const mavlink_message_t &msg)
|
||||||
green_blink_count = 1;
|
green_blink_count = 1;
|
||||||
last_video_ms = AP_HAL::millis();
|
last_video_ms = AP_HAL::millis();
|
||||||
// immediately update AP_Notify recording flag
|
// immediately update AP_Notify recording flag
|
||||||
AP_Notify::flags.video_recording = 1;
|
AP_Notify::flags.video_recording = true;
|
||||||
} else if (strncmp(m.name, "WIFICHAN", 10) == 0) {
|
} else if (strncmp(m.name, "WIFICHAN", 10) == 0) {
|
||||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||||
AP_Radio *radio = AP_Radio::get_singleton();
|
AP_Radio *radio = AP_Radio::get_singleton();
|
||||||
|
|
Loading…
Reference in New Issue