|
|
|
@ -110,20 +110,20 @@ void Tracker::init_tracker()
@@ -110,20 +110,20 @@ void Tracker::init_tracker()
|
|
|
|
|
|
|
|
|
|
switch (g.initial_mode) { |
|
|
|
|
case MANUAL: |
|
|
|
|
set_mode(MANUAL, MODE_REASON_STARTUP); |
|
|
|
|
set_mode(MANUAL, ModeReason::STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case SCAN: |
|
|
|
|
set_mode(SCAN, MODE_REASON_STARTUP); |
|
|
|
|
set_mode(SCAN, ModeReason::STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case STOP: |
|
|
|
|
set_mode(STOP, MODE_REASON_STARTUP); |
|
|
|
|
set_mode(STOP, ModeReason::STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUTO: |
|
|
|
|
default: |
|
|
|
|
set_mode(AUTO, MODE_REASON_STARTUP); |
|
|
|
|
set_mode(AUTO, ModeReason::STARTUP); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -214,7 +214,7 @@ void Tracker::prepare_servos()
@@ -214,7 +214,7 @@ void Tracker::prepare_servos()
|
|
|
|
|
SRV_Channels::output_ch_all(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason) |
|
|
|
|
void Tracker::set_mode(enum ControlMode mode, ModeReason reason) |
|
|
|
|
{ |
|
|
|
|
if (control_mode == mode) { |
|
|
|
|
// don't switch modes if we are already in the correct mode.
|
|
|
|
@ -243,6 +243,20 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
@@ -243,6 +243,20 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
|
|
|
|
|
nav_status.bearing = ahrs.yaw_sensor * 0.01f; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool Tracker::set_mode(const uint8_t new_mode, const ModeReason reason) |
|
|
|
|
{ |
|
|
|
|
switch (new_mode) { |
|
|
|
|
case AUTO: |
|
|
|
|
case MANUAL: |
|
|
|
|
case SCAN: |
|
|
|
|
case SERVO_TEST: |
|
|
|
|
case STOP: |
|
|
|
|
set_mode((enum ControlMode)new_mode, reason); |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
should we log a message type now? |
|
|
|
|
*/ |
|
|
|
|