mirror of https://github.com/ArduPilot/ardupilot
Tracker: add reason to set_mode
This commit is contained in:
parent
dc5ef168fd
commit
f844f4ea80
|
@ -569,7 +569,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|||
|
||||
// mavproxy/mavutil sends this when auto command is entered
|
||||
case MAV_CMD_MISSION_START:
|
||||
tracker.set_mode(AUTO);
|
||||
tracker.set_mode(AUTO, MODE_REASON_GCS_COMMAND);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
|
@ -816,7 +816,7 @@ bool GCS_MAVLINK_Tracker::set_mode(uint8_t mode)
|
|||
case SCAN:
|
||||
case SERVO_TEST:
|
||||
case STOP:
|
||||
tracker.set_mode((enum ControlMode)mode);
|
||||
tracker.set_mode((enum ControlMode)mode, MODE_REASON_GCS_COMMAND);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
|
|
@ -83,7 +83,7 @@ const struct LogStructure Tracker::log_structure[] = {
|
|||
|
||||
void Tracker::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
DataFlash.Log_Write_Mode(control_mode);
|
||||
DataFlash.Log_Write_Mode(control_mode, MODE_REASON_INITIALISED);
|
||||
gps.Write_DataFlash_Log_Startup_messages();
|
||||
}
|
||||
|
||||
|
|
|
@ -244,7 +244,7 @@ private:
|
|||
void arm_servos();
|
||||
void disarm_servos();
|
||||
void prepare_servos();
|
||||
void set_mode(enum ControlMode mode);
|
||||
void set_mode(enum ControlMode mode, mode_reason_t reason);
|
||||
void check_usb_mux(void);
|
||||
void update_vehicle_pos_estimate();
|
||||
void update_tracker_position();
|
||||
|
|
|
@ -20,7 +20,7 @@ bool Tracker::servo_test_set_servo(uint8_t servo_num, uint16_t pwm)
|
|||
|
||||
// ensure we are in servo test mode
|
||||
if (control_mode != SERVO_TEST) {
|
||||
set_mode(SERVO_TEST);
|
||||
set_mode(SERVO_TEST, MODE_REASON_SERVOTEST);
|
||||
}
|
||||
|
||||
// set yaw servo pwm and send output to servo
|
||||
|
|
|
@ -29,6 +29,13 @@ enum AltSource {
|
|||
ALT_SOURCE_GPS_VEH_ONLY=2
|
||||
};
|
||||
|
||||
enum mode_reason_t {
|
||||
MODE_REASON_INITIALISED = 0,
|
||||
MODE_REASON_STARTUP,
|
||||
MODE_REASON_SERVOTEST,
|
||||
MODE_REASON_GCS_COMMAND,
|
||||
};
|
||||
|
||||
// Filter
|
||||
#define SERVO_OUT_FILT_HZ 0.1f
|
||||
#define G_Dt 0.02f
|
||||
|
|
|
@ -110,7 +110,7 @@ void Tracker::init_tracker()
|
|||
gcs().send_text(MAV_SEVERITY_INFO,"Ready to track");
|
||||
hal.scheduler->delay(1000); // Why????
|
||||
|
||||
set_mode(AUTO); // tracking
|
||||
set_mode(AUTO, MODE_REASON_STARTUP); // tracking
|
||||
|
||||
if (g.startup_delay > 0) {
|
||||
// arm servos with trim value to allow them to start up (required
|
||||
|
@ -211,7 +211,7 @@ void Tracker::prepare_servos()
|
|||
SRV_Channels::output_ch_all();
|
||||
}
|
||||
|
||||
void Tracker::set_mode(enum ControlMode mode)
|
||||
void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
|
||||
{
|
||||
if (control_mode == mode) {
|
||||
// don't switch modes if we are already in the correct mode.
|
||||
|
@ -234,7 +234,7 @@ void Tracker::set_mode(enum ControlMode mode)
|
|||
}
|
||||
|
||||
// log mode change
|
||||
DataFlash.Log_Write_Mode(control_mode);
|
||||
DataFlash.Log_Write_Mode(control_mode, reason);
|
||||
}
|
||||
|
||||
void Tracker::check_usb_mux(void)
|
||||
|
|
Loading…
Reference in New Issue