Tracker: Support new AP_Vehicle::set_mode

This commit is contained in:
Michael du Breuil 2019-10-16 20:49:06 -07:00 committed by Randy Mackay
parent a1acc75e11
commit 6d7b196212
7 changed files with 24 additions and 35 deletions

View File

@ -406,7 +406,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command
// mavproxy/mavutil sends this when auto command is entered
case MAV_CMD_MISSION_START:
tracker.set_mode(AUTO, MODE_REASON_GCS_COMMAND);
tracker.set_mode(AUTO, ModeReason::GCS_COMMAND);
return MAV_RESULT_ACCEPTED;
default:
@ -607,23 +607,6 @@ void Tracker::mavlink_delay_cb()
logger.EnableWrites(true);
}
/*
set_mode() wrapper for MAVLink SET_MODE
*/
bool GCS_MAVLINK_Tracker::set_mode(uint8_t mode)
{
switch (mode) {
case AUTO:
case MANUAL:
case SCAN:
case SERVO_TEST:
case STOP:
tracker.set_mode((enum ControlMode)mode, MODE_REASON_GCS_COMMAND);
return true;
}
return false;
}
// send position tracker is using
void GCS_MAVLINK_Tracker::send_global_position_int()
{

View File

@ -18,8 +18,6 @@ protected:
uint8_t sysid_my_gcs() const override;
bool set_mode(uint8_t mode) override;
MAV_RESULT _handle_command_preflight_calibration_baro() override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;

View File

@ -78,7 +78,7 @@ const struct LogStructure Tracker::log_structure[] = {
void Tracker::Log_Write_Vehicle_Startup_Messages()
{
logger.Write_Mode(control_mode, MODE_REASON_INITIALISED);
logger.Write_Mode(control_mode, ModeReason::INITIALISED);
gps.Write_AP_Logger_Log_Startup_messages();
}

View File

@ -246,7 +246,8 @@ private:
void arm_servos();
void disarm_servos();
void prepare_servos();
void set_mode(enum ControlMode mode, mode_reason_t reason);
void set_mode(enum ControlMode mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
bool should_log(uint32_t mask);
bool start_command_callback(const AP_Mission::Mission_Command& cmd) { return false; }
void exit_mission_callback() { return; }

View File

@ -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, MODE_REASON_SERVOTEST);
set_mode(SERVO_TEST, ModeReason::SERVOTEST);
}
// set yaw servo pwm and send output to servo

View File

@ -24,13 +24,6 @@ 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,
};
enum class PWMDisarmed {
ZERO = 0,
TRIM,

View File

@ -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()
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)
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?
*/