|
|
|
@ -101,7 +101,24 @@ void Tracker::init_tracker()
@@ -101,7 +101,24 @@ void Tracker::init_tracker()
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"Ready to track"); |
|
|
|
|
hal.scheduler->delay(1000); // Why????
|
|
|
|
|
|
|
|
|
|
set_mode(AUTO, MODE_REASON_STARTUP); // tracking
|
|
|
|
|
switch (g.initial_mode) { |
|
|
|
|
case MANUAL: |
|
|
|
|
set_mode(MANUAL, MODE_REASON_STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case SCAN: |
|
|
|
|
set_mode(SCAN, MODE_REASON_STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case STOP: |
|
|
|
|
set_mode(STOP, MODE_REASON_STARTUP); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case AUTO: |
|
|
|
|
default: |
|
|
|
|
set_mode(AUTO, MODE_REASON_STARTUP); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (g.startup_delay > 0) { |
|
|
|
|
// arm servos with trim value to allow them to start up (required
|
|
|
|
|