mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: cope with change in namespace of LogEvent enum
Also move Acro Trainer types into an enum class as the global defines interfere with the Event names. Also eliminate the Log_Write_Event wrappers.
This commit is contained in:
parent
daf071f7f6
commit
e6c6189fe5
@ -693,7 +693,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
|
||||
if (!ahrs.home_is_set()) {
|
||||
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
|
||||
ahrs.resetHeightDatum();
|
||||
AP::logger().Write_Event(DATA_EKF_ALT_RESET);
|
||||
AP::logger().Write_Event(LogEvent::EKF_ALT_RESET);
|
||||
|
||||
// we have reset height, so arming height is zero
|
||||
copter.arming_altitude_m = 0;
|
||||
@ -728,7 +728,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
|
||||
// finally actually arm the motors
|
||||
copter.motors->armed(true);
|
||||
|
||||
AP::logger().Write_Event(DATA_ARMED);
|
||||
AP::logger().Write_Event(LogEvent::ARMED);
|
||||
|
||||
// log flight mode in case it was changed while vehicle was disarmed
|
||||
AP::logger().Write_Mode((uint8_t)copter.control_mode, copter.control_mode_reason);
|
||||
@ -797,7 +797,7 @@ bool AP_Arming_Copter::disarm()
|
||||
copter.set_land_complete(true);
|
||||
copter.set_land_complete_maybe(true);
|
||||
|
||||
AP::logger().Write_Event(DATA_DISARMED);
|
||||
AP::logger().Write_Event(LogEvent::DISARMED);
|
||||
|
||||
// send disarm command to motors
|
||||
copter.motors->armed(false);
|
||||
|
@ -9,7 +9,7 @@ void Copter::set_auto_armed(bool b)
|
||||
|
||||
ap.auto_armed = b;
|
||||
if(b){
|
||||
Log_Write_Event(DATA_AUTO_ARMED);
|
||||
AP::logger().Write_Event(LogEvent::AUTO_ARMED);
|
||||
}
|
||||
}
|
||||
|
||||
@ -24,18 +24,18 @@ void Copter::set_simple_mode(uint8_t b)
|
||||
if (ap.simple_mode != b) {
|
||||
switch (b) {
|
||||
case 0:
|
||||
Log_Write_Event(DATA_SET_SIMPLE_OFF);
|
||||
AP::logger().Write_Event(LogEvent::SET_SIMPLE_OFF);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");
|
||||
break;
|
||||
case 1:
|
||||
Log_Write_Event(DATA_SET_SIMPLE_ON);
|
||||
AP::logger().Write_Event(LogEvent::SET_SIMPLE_ON);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");
|
||||
break;
|
||||
case 2:
|
||||
default:
|
||||
// initialise super simple heading
|
||||
update_super_simple_bearing(true);
|
||||
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
|
||||
AP::logger().Write_Event(LogEvent::SET_SUPERSIMPLE_ON);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
|
||||
break;
|
||||
}
|
||||
|
@ -428,7 +428,7 @@ void Copter::three_hz_loop()
|
||||
void Copter::one_hz_loop()
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
Log_Write_Data(DATA_AP_STATE, ap.value);
|
||||
Log_Write_Data(LogDataID::AP_STATE, ap.value);
|
||||
}
|
||||
|
||||
arming.update();
|
||||
@ -498,7 +498,7 @@ void Copter::init_simple_bearing()
|
||||
|
||||
// log the simple bearing
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
Log_Write_Data(DATA_INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
|
||||
Log_Write_Data(LogDataID::INIT_SIMPLE_BEARING, ahrs.yaw_sensor);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -774,12 +774,11 @@ private:
|
||||
void Log_Write_Attitude();
|
||||
void Log_Write_EKF_POS();
|
||||
void Log_Write_MotBatt();
|
||||
void Log_Write_Event(Log_Event id);
|
||||
void Log_Write_Data(uint8_t id, int32_t value);
|
||||
void Log_Write_Data(uint8_t id, uint32_t value);
|
||||
void Log_Write_Data(uint8_t id, int16_t value);
|
||||
void Log_Write_Data(uint8_t id, uint16_t value);
|
||||
void Log_Write_Data(uint8_t id, float value);
|
||||
void Log_Write_Data(LogDataID id, int32_t value);
|
||||
void Log_Write_Data(LogDataID id, uint32_t value);
|
||||
void Log_Write_Data(LogDataID id, int16_t value);
|
||||
void Log_Write_Data(LogDataID id, uint16_t value);
|
||||
void Log_Write_Data(LogDataID id, float value);
|
||||
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);
|
||||
void Log_Sensor_Health();
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
@ -720,11 +720,11 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
switch ((uint16_t)packet.param1) {
|
||||
case PARACHUTE_DISABLE:
|
||||
copter.parachute.enabled(false);
|
||||
copter.Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
AP::logger().Write_Event(LogEvent::PARACHUTE_DISABLED);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case PARACHUTE_ENABLE:
|
||||
copter.parachute.enabled(true);
|
||||
copter.Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
AP::logger().Write_Event(LogEvent::PARACHUTE_ENABLED);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case PARACHUTE_RELEASE:
|
||||
// treat as a manual release which performs some additional check of altitude
|
||||
@ -758,17 +758,17 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
switch ((uint8_t)packet.param2) {
|
||||
case WINCH_RELAXED:
|
||||
copter.g2.winch.relax();
|
||||
copter.Log_Write_Event(DATA_WINCH_RELAXED);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_RELAXED);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case WINCH_RELATIVE_LENGTH_CONTROL: {
|
||||
copter.g2.winch.release_length(packet.param3, fabsf(packet.param4));
|
||||
copter.Log_Write_Event(DATA_WINCH_LENGTH_CONTROL);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_LENGTH_CONTROL);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
case WINCH_RATE_CONTROL:
|
||||
if (fabsf(packet.param4) <= copter.g2.winch.get_rate_max()) {
|
||||
copter.g2.winch.set_desired_rate(packet.param4);
|
||||
copter.Log_Write_Event(DATA_WINCH_RATE_CONTROL);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_RATE_CONTROL);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
@ -118,12 +118,6 @@ void Copter::Log_Write_MotBatt()
|
||||
#endif
|
||||
}
|
||||
|
||||
// Wrote an event packet
|
||||
void Copter::Log_Write_Event(Log_Event id)
|
||||
{
|
||||
logger.Write_Event(id);
|
||||
}
|
||||
|
||||
struct PACKED log_Data_Int16t {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
@ -133,13 +127,13 @@ struct PACKED log_Data_Int16t {
|
||||
|
||||
// Write an int16_t data packet
|
||||
UNUSED_FUNCTION
|
||||
void Copter::Log_Write_Data(uint8_t id, int16_t value)
|
||||
void Copter::Log_Write_Data(LogDataID id, int16_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Int16t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -155,13 +149,13 @@ struct PACKED log_Data_UInt16t {
|
||||
|
||||
// Write an uint16_t data packet
|
||||
UNUSED_FUNCTION
|
||||
void Copter::Log_Write_Data(uint8_t id, uint16_t value)
|
||||
void Copter::Log_Write_Data(LogDataID id, uint16_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_UInt16t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -176,13 +170,13 @@ struct PACKED log_Data_Int32t {
|
||||
};
|
||||
|
||||
// Write an int32_t data packet
|
||||
void Copter::Log_Write_Data(uint8_t id, int32_t value)
|
||||
void Copter::Log_Write_Data(LogDataID id, int32_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Int32t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -197,13 +191,13 @@ struct PACKED log_Data_UInt32t {
|
||||
};
|
||||
|
||||
// Write a uint32_t data packet
|
||||
void Copter::Log_Write_Data(uint8_t id, uint32_t value)
|
||||
void Copter::Log_Write_Data(LogDataID id, uint32_t value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_UInt32t pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -219,13 +213,13 @@ struct PACKED log_Data_Float {
|
||||
|
||||
// Write a float data packet
|
||||
UNUSED_FUNCTION
|
||||
void Copter::Log_Write_Data(uint8_t id, float value)
|
||||
void Copter::Log_Write_Data(LogDataID id, float value)
|
||||
{
|
||||
if (should_log(MASK_LOG_ANY)) {
|
||||
struct log_Data_Float pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
id : id,
|
||||
id : (uint8_t)id,
|
||||
data_value : value
|
||||
};
|
||||
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
@ -274,7 +268,7 @@ void Copter::Log_Sensor_Health()
|
||||
// check primary GPS
|
||||
if (sensor_health.primary_gps != gps.primary_sensor()) {
|
||||
sensor_health.primary_gps = gps.primary_sensor();
|
||||
Log_Write_Event(DATA_GPS_PRIMARY_CHANGED);
|
||||
AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);
|
||||
}
|
||||
}
|
||||
|
||||
@ -513,12 +507,11 @@ void Copter::Log_Write_Performance() {}
|
||||
void Copter::Log_Write_Attitude(void) {}
|
||||
void Copter::Log_Write_EKF_POS() {}
|
||||
void Copter::Log_Write_MotBatt() {}
|
||||
void Copter::Log_Write_Event(Log_Event id) {}
|
||||
void Copter::Log_Write_Data(uint8_t id, int32_t value) {}
|
||||
void Copter::Log_Write_Data(uint8_t id, uint32_t value) {}
|
||||
void Copter::Log_Write_Data(uint8_t id, int16_t value) {}
|
||||
void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
|
||||
void Copter::Log_Write_Data(uint8_t id, float value) {}
|
||||
void Copter::Log_Write_Data(LogDataID id, int32_t value) {}
|
||||
void Copter::Log_Write_Data(LogDataID id, uint32_t value) {}
|
||||
void Copter::Log_Write_Data(LogDataID id, int16_t value) {}
|
||||
void Copter::Log_Write_Data(LogDataID id, uint16_t value) {}
|
||||
void Copter::Log_Write_Data(LogDataID id, float value) {}
|
||||
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {}
|
||||
void Copter::Log_Sensor_Health() {}
|
||||
void Copter::Log_Write_Precland() {}
|
||||
|
@ -455,7 +455,7 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @Description: Type of trainer used in acro mode
|
||||
// @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
|
||||
// @User: Advanced
|
||||
GSCALAR(acro_trainer, "ACRO_TRAINER", ACRO_TRAINER_LIMITED),
|
||||
GSCALAR(acro_trainer, "ACRO_TRAINER", (uint8_t)ModeAcro::Trainer::LIMITED),
|
||||
|
||||
// @Param: ACRO_RP_EXPO
|
||||
// @DisplayName: Acro Roll/Pitch Expo
|
||||
|
@ -205,7 +205,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
// only altitude will matter to the AP mission script for takeoff.
|
||||
if (copter.mode_auto.mission.add_cmd(cmd)) {
|
||||
// log event
|
||||
copter.Log_Write_Event(DATA_SAVEWP_ADD_WP);
|
||||
AP::logger().Write_Event(LogEvent::SAVEWP_ADD_WP);
|
||||
}
|
||||
}
|
||||
|
||||
@ -223,7 +223,7 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
// save command
|
||||
if (copter.mode_auto.mission.add_cmd(cmd)) {
|
||||
// log event
|
||||
copter.Log_Write_Event(DATA_SAVEWP_ADD_WP);
|
||||
AP::logger().Write_Event(LogEvent::SAVEWP_ADD_WP);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@ -250,16 +250,16 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
switch(ch_flag) {
|
||||
case LOW:
|
||||
copter.g.acro_trainer = ACRO_TRAINER_DISABLED;
|
||||
copter.Log_Write_Event(DATA_ACRO_TRAINER_DISABLED);
|
||||
copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::OFF;
|
||||
AP::logger().Write_Event(LogEvent::ACRO_TRAINER_OFF);
|
||||
break;
|
||||
case MIDDLE:
|
||||
copter.g.acro_trainer = ACRO_TRAINER_LEVELING;
|
||||
copter.Log_Write_Event(DATA_ACRO_TRAINER_LEVELING);
|
||||
copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LEVELING;
|
||||
AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LEVELING);
|
||||
break;
|
||||
case HIGH:
|
||||
copter.g.acro_trainer = ACRO_TRAINER_LIMITED;
|
||||
copter.Log_Write_Event(DATA_ACRO_TRAINER_LIMITED);
|
||||
copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LIMITED;
|
||||
AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LIMITED);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
@ -308,11 +308,11 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
switch (ch_flag) {
|
||||
case LOW:
|
||||
copter.parachute.enabled(false);
|
||||
copter.Log_Write_Event(DATA_PARACHUTE_DISABLED);
|
||||
AP::logger().Write_Event(LogEvent::PARACHUTE_DISABLED);
|
||||
break;
|
||||
case MIDDLE:
|
||||
copter.parachute.enabled(true);
|
||||
copter.Log_Write_Event(DATA_PARACHUTE_ENABLED);
|
||||
AP::logger().Write_Event(LogEvent::PARACHUTE_ENABLED);
|
||||
break;
|
||||
case HIGH:
|
||||
copter.parachute.enabled(true);
|
||||
@ -371,10 +371,10 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
// enable or disable AP_Avoidance
|
||||
if (ch_flag == HIGH) {
|
||||
copter.avoidance_adsb.enable();
|
||||
copter.Log_Write_Event(DATA_AVOIDANCE_ADSB_ENABLE);
|
||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE);
|
||||
} else {
|
||||
copter.avoidance_adsb.disable();
|
||||
copter.Log_Write_Event(DATA_AVOIDANCE_ADSB_DISABLE);
|
||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
@ -444,12 +444,12 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
case HIGH:
|
||||
// high switch maintains current position
|
||||
copter.g2.winch.release_length(0.0f);
|
||||
copter.Log_Write_Event(DATA_WINCH_LENGTH_CONTROL);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_LENGTH_CONTROL);
|
||||
break;
|
||||
default:
|
||||
// all other position relax winch
|
||||
copter.g2.winch.relax();
|
||||
copter.Log_Write_Event(DATA_WINCH_RELAXED);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_RELAXED);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
@ -547,12 +547,12 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
switch (ch_flag) {
|
||||
case HIGH:
|
||||
copter.standby_active = true;
|
||||
copter.Log_Write_Event(DATA_STANDBY_ENABLE);
|
||||
AP::logger().Write_Event(LogEvent::STANDBY_ENABLE);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Stand By Enabled");
|
||||
break;
|
||||
default:
|
||||
copter.standby_active = false;
|
||||
copter.Log_Write_Event(DATA_STANDBY_DISABLE);
|
||||
AP::logger().Write_Event(LogEvent::STANDBY_DISABLE);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Stand By Disabled");
|
||||
break;
|
||||
}
|
||||
@ -586,7 +586,7 @@ void Copter::save_trim()
|
||||
float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f);
|
||||
float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f);
|
||||
ahrs.add_trim(roll_trim, pitch_trim);
|
||||
Log_Write_Event(DATA_SAVE_TRIM);
|
||||
AP::logger().Write_Event(LogEvent::SAVE_TRIM);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Trim saved");
|
||||
}
|
||||
|
||||
|
@ -79,7 +79,7 @@ bool Copter::set_home(const Location& loc, bool lock)
|
||||
// init inav and compass declination
|
||||
if (!home_was_set) {
|
||||
// record home is set
|
||||
Log_Write_Event(DATA_SET_HOME);
|
||||
AP::logger().Write_Event(LogEvent::SET_HOME);
|
||||
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
// log new home position which mission library will pull from ahrs
|
||||
|
@ -76,11 +76,6 @@ enum tuning_func {
|
||||
TUNING_SYSTEM_ID_MAGNITUDE = 58 // magnitude of the system ID signal
|
||||
};
|
||||
|
||||
// Acro Trainer types
|
||||
#define ACRO_TRAINER_DISABLED 0
|
||||
#define ACRO_TRAINER_LEVELING 1
|
||||
#define ACRO_TRAINER_LIMITED 2
|
||||
|
||||
// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
|
||||
#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
|
||||
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
|
||||
|
@ -191,7 +191,7 @@ void Copter::check_ekf_reset()
|
||||
if (new_ekfYawReset_ms != ekfYawReset_ms) {
|
||||
attitude_control->inertial_frame_reset();
|
||||
ekfYawReset_ms = new_ekfYawReset_ms;
|
||||
Log_Write_Event(DATA_EKF_YAW_RESET);
|
||||
AP::logger().Write_Event(LogEvent::EKF_YAW_RESET);
|
||||
}
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
@ -173,9 +173,9 @@ void Copter::heli_update_rotor_speed_targets()
|
||||
|
||||
// when rotor_runup_complete changes to true, log event
|
||||
if (!rotor_runup_complete_last && motors->rotor_runup_complete()){
|
||||
Log_Write_Event(DATA_ROTOR_RUNUP_COMPLETE);
|
||||
AP::logger().Write_Event(LogEvent::ROTOR_RUNUP_COMPLETE);
|
||||
} else if (rotor_runup_complete_last && !motors->rotor_runup_complete()){
|
||||
Log_Write_Event(DATA_ROTOR_SPEED_BELOW_CRITICAL);
|
||||
AP::logger().Write_Event(LogEvent::ROTOR_SPEED_BELOW_CRITICAL);
|
||||
}
|
||||
rotor_runup_complete_last = motors->rotor_runup_complete();
|
||||
}
|
||||
|
@ -102,9 +102,9 @@ void Copter::set_land_complete(bool b)
|
||||
land_detector_count = 0;
|
||||
|
||||
if(b){
|
||||
Log_Write_Event(DATA_LAND_COMPLETE);
|
||||
AP::logger().Write_Event(LogEvent::LAND_COMPLETE);
|
||||
} else {
|
||||
Log_Write_Event(DATA_NOT_LANDED);
|
||||
AP::logger().Write_Event(LogEvent::NOT_LANDED);
|
||||
}
|
||||
ap.land_complete = b;
|
||||
|
||||
@ -132,7 +132,7 @@ void Copter::set_land_complete_maybe(bool b)
|
||||
return;
|
||||
|
||||
if (b) {
|
||||
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
|
||||
AP::logger().Write_Event(LogEvent::LAND_COMPLETE_MAYBE);
|
||||
}
|
||||
ap.land_complete_maybe = b;
|
||||
}
|
||||
|
@ -21,9 +21,9 @@ void Copter::landinggear_update()
|
||||
// send event message to datalog if status has changed
|
||||
if (landinggear.deployed() != last_deploy_status) {
|
||||
if (landinggear.deployed()) {
|
||||
Log_Write_Event(DATA_LANDING_GEAR_DEPLOYED);
|
||||
AP::logger().Write_Event(LogEvent::LANDING_GEAR_DEPLOYED);
|
||||
} else {
|
||||
Log_Write_Event(DATA_LANDING_GEAR_RETRACTED);
|
||||
AP::logger().Write_Event(LogEvent::LANDING_GEAR_RETRACTED);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -552,7 +552,7 @@ void Mode::land_run_horizontal_control()
|
||||
// process pilot inputs
|
||||
if (!copter.failsafe.radio) {
|
||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||
copter.Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||
AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT);
|
||||
// exit land if throttle is high
|
||||
if (!set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) {
|
||||
set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE);
|
||||
@ -569,7 +569,7 @@ void Mode::land_run_horizontal_control()
|
||||
// record if pilot has overridden roll or pitch
|
||||
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
|
||||
if (!copter.ap.land_repo_active) {
|
||||
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);
|
||||
AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE);
|
||||
}
|
||||
copter.ap.land_repo_active = true;
|
||||
}
|
||||
@ -765,11 +765,6 @@ GCS_Copter &Mode::gcs()
|
||||
return copter.gcs();
|
||||
}
|
||||
|
||||
void Mode::Log_Write_Event(Log_Event id)
|
||||
{
|
||||
return copter.logger.Write_Event(id);
|
||||
}
|
||||
|
||||
void Mode::set_throttle_takeoff()
|
||||
{
|
||||
return copter.set_throttle_takeoff();
|
||||
|
@ -241,7 +241,6 @@ public:
|
||||
bool set_mode(Mode::Number mode, ModeReason reason);
|
||||
void set_land_complete(bool b);
|
||||
GCS_Copter &gcs();
|
||||
void Log_Write_Event(Log_Event id);
|
||||
void set_throttle_takeoff(void);
|
||||
float get_avoidance_adjusted_climbrate(float target_rate);
|
||||
uint16_t get_pilot_speed_dn(void);
|
||||
@ -257,6 +256,12 @@ public:
|
||||
// inherit constructor
|
||||
using Mode::Mode;
|
||||
|
||||
enum class Trainer {
|
||||
OFF = 0,
|
||||
LEVELING = 1,
|
||||
LIMITED = 2,
|
||||
};
|
||||
|
||||
virtual void run() override;
|
||||
|
||||
bool requires_GPS() const override { return false; }
|
||||
|
@ -111,7 +111,7 @@ void ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in,
|
||||
|
||||
// calculate earth frame rate corrections to pull the copter back to level while in ACRO mode
|
||||
|
||||
if (g.acro_trainer != ACRO_TRAINER_DISABLED) {
|
||||
if (g.acro_trainer != (uint8_t)Trainer::OFF) {
|
||||
|
||||
// get attitude targets
|
||||
const Vector3f att_target = attitude_control->get_att_target_euler_cd();
|
||||
@ -128,7 +128,7 @@ void ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in,
|
||||
rate_ef_level.z = 0;
|
||||
|
||||
// Calculate angle limiting earth frame rate commands
|
||||
if (g.acro_trainer == ACRO_TRAINER_LIMITED) {
|
||||
if (g.acro_trainer == (uint8_t)Trainer::LIMITED) {
|
||||
const float angle_max = copter.aparm.angle_max;
|
||||
if (roll_angle > angle_max){
|
||||
rate_ef_level.x += AC_AttitudeControl::sqrt_controller(angle_max - roll_angle, g.acro_rp_p * 4.5, attitude_control->get_accel_roll_max(), G_Dt);
|
||||
@ -147,7 +147,7 @@ void ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in,
|
||||
attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level);
|
||||
|
||||
// combine earth frame rate corrections with rate requests
|
||||
if (g.acro_trainer == ACRO_TRAINER_LIMITED) {
|
||||
if (g.acro_trainer == (uint8_t)Trainer::LIMITED) {
|
||||
rate_bf_request.x += rate_bf_level.x;
|
||||
rate_bf_request.y += rate_bf_level.y;
|
||||
rate_bf_request.z += rate_bf_level.z;
|
||||
|
@ -71,7 +71,7 @@ void ModeAcro_Heli::run()
|
||||
// convert the input to the desired body frame rate
|
||||
get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
|
||||
// only mimic flybar response when trainer mode is disabled
|
||||
if (g.acro_trainer == ACRO_TRAINER_DISABLED) {
|
||||
if ((Trainer)g.acro_trainer.get() == Trainer::OFF) {
|
||||
// while landed always leak off target attitude to current attitude
|
||||
if (copter.ap.land_complete) {
|
||||
virtual_flybar(target_roll, target_pitch, target_yaw, 3.0f, 3.0f);
|
||||
|
@ -1456,15 +1456,15 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd)
|
||||
switch (cmd.content.winch.action) {
|
||||
case WINCH_RELAXED:
|
||||
g2.winch.relax();
|
||||
Log_Write_Event(DATA_WINCH_RELAXED);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_RELAXED);
|
||||
break;
|
||||
case WINCH_RELATIVE_LENGTH_CONTROL:
|
||||
g2.winch.release_length(cmd.content.winch.release_length, cmd.content.winch.release_rate);
|
||||
Log_Write_Event(DATA_WINCH_LENGTH_CONTROL);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_LENGTH_CONTROL);
|
||||
break;
|
||||
case WINCH_RATE_CONTROL:
|
||||
g2.winch.set_desired_rate(cmd.content.winch.release_rate);
|
||||
Log_Write_Event(DATA_WINCH_RATE_CONTROL);
|
||||
AP::logger().Write_Event(LogEvent::WINCH_RATE_CONTROL);
|
||||
break;
|
||||
default:
|
||||
// do nothing
|
||||
|
@ -79,7 +79,7 @@ bool ModeFlip::init(bool ignore_checks)
|
||||
}
|
||||
|
||||
// log start of flip
|
||||
Log_Write_Event(DATA_FLIP_START);
|
||||
AP::logger().Write_Event(LogEvent::FLIP_START);
|
||||
|
||||
// capture current attitude which will be used during the FlipState::Recovery stage
|
||||
const float angle_max = copter.aparm.angle_max;
|
||||
@ -197,7 +197,7 @@ void ModeFlip::run()
|
||||
copter.set_mode(Mode::Number::STABILIZE, ModeReason::UNKNOWN);
|
||||
}
|
||||
// log successful completion
|
||||
Log_Write_Event(DATA_FLIP_END);
|
||||
AP::logger().Write_Event(LogEvent::FLIP_END);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -91,7 +91,7 @@ void ModeLand::nogps_run()
|
||||
// process pilot inputs
|
||||
if (!copter.failsafe.radio) {
|
||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||
AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT);
|
||||
// exit land if throttle is high
|
||||
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE);
|
||||
}
|
||||
|
@ -285,7 +285,7 @@ void ModeRTL::descent_run()
|
||||
// process pilot's input
|
||||
if (!copter.failsafe.radio) {
|
||||
if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
|
||||
Log_Write_Event(DATA_LAND_CANCELLED_BY_PILOT);
|
||||
AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT);
|
||||
// exit land if throttle is high
|
||||
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) {
|
||||
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE);
|
||||
@ -302,7 +302,7 @@ void ModeRTL::descent_run()
|
||||
// record if pilot has overridden roll or pitch
|
||||
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
|
||||
if (!copter.ap.land_repo_active) {
|
||||
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);
|
||||
AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE);
|
||||
}
|
||||
copter.ap.land_repo_active = true;
|
||||
}
|
||||
|
@ -81,13 +81,13 @@ void ModeZigZag::save_or_move_to_destination(uint8_t dest_num)
|
||||
dest_A.x = curr_pos.x;
|
||||
dest_A.y = curr_pos.y;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point A stored");
|
||||
copter.Log_Write_Event(DATA_ZIGZAG_STORE_A);
|
||||
AP::logger().Write_Event(LogEvent::ZIGZAG_STORE_A);
|
||||
} else {
|
||||
// store point B
|
||||
dest_B.x = curr_pos.x;
|
||||
dest_B.y = curr_pos.y;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point B stored");
|
||||
copter.Log_Write_Event(DATA_ZIGZAG_STORE_B);
|
||||
AP::logger().Write_Event(LogEvent::ZIGZAG_STORE_B);
|
||||
}
|
||||
// if both A and B have been stored advance state
|
||||
if (!dest_A.is_zero() && !dest_B.is_zero() && is_positive((dest_B - dest_A).length_squared())) {
|
||||
|
@ -166,10 +166,10 @@ void Copter::motors_output()
|
||||
bool interlock = motors->armed() && !ap.in_arming_delay && (!ap.using_interlock || ap.motor_interlock_switch) && !SRV_Channels::get_emergency_stop();
|
||||
if (!motors->get_interlock() && interlock) {
|
||||
motors->set_interlock(true);
|
||||
Log_Write_Event(DATA_MOTORS_INTERLOCK_ENABLED);
|
||||
AP::logger().Write_Event(LogEvent::MOTORS_INTERLOCK_ENABLED);
|
||||
} else if (motors->get_interlock() && !interlock) {
|
||||
motors->set_interlock(false);
|
||||
Log_Write_Event(DATA_MOTORS_INTERLOCK_DISABLED);
|
||||
AP::logger().Write_Event(LogEvent::MOTORS_INTERLOCK_DISABLED);
|
||||
}
|
||||
|
||||
// send output signals to motors
|
||||
|
Loading…
Reference in New Issue
Block a user