mirror of https://github.com/ArduPilot/ardupilot
Tracker: add initial mode parameter
This commit is contained in:
parent
392b59d7d6
commit
1ac74e2fe5
|
@ -403,6 +403,12 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(scan_speed_pitch, "SCAN_SPEED_PIT", 5),
|
||||
|
||||
// @Param: INITIAL_MODE
|
||||
// @DisplayName: Mode tracker will switch into after initialization
|
||||
// @Description: 0:MANUAL, 1:STOP, 2:SCAN, 10:AUTO
|
||||
// @User: Standard
|
||||
GSCALAR(initial_mode, "INITIAL_MODE", 10),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -119,6 +119,7 @@ public:
|
|||
k_param_gcs_pid_mask = 225,
|
||||
k_param_scan_speed_yaw,
|
||||
k_param_scan_speed_pitch,
|
||||
k_param_initial_mode
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
@ -156,6 +157,7 @@ public:
|
|||
AP_Int16 pitch_min;
|
||||
AP_Int16 pitch_max;
|
||||
AP_Int16 gcs_pid_mask;
|
||||
AP_Int8 initial_mode;
|
||||
|
||||
// Waypoints
|
||||
//
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue