mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
4cf71de646
commit
fdfe6eeb65
|
@ -877,14 +877,14 @@ void RC_Channel::do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
avoidance->enable();
|
avoidance->enable();
|
||||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE);
|
LOGGER_WRITE_EVENT(LogEvent::AVOIDANCE_ADSB_ENABLE);
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled");
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// disable AP_Avoidance
|
// disable AP_Avoidance
|
||||||
avoidance->disable();
|
avoidance->disable();
|
||||||
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE);
|
LOGGER_WRITE_EVENT(LogEvent::AVOIDANCE_ADSB_DISABLE);
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled");
|
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -1216,6 +1216,7 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun
|
||||||
#endif
|
#endif
|
||||||
const bool ret = do_aux_function(ch_option, pos);
|
const bool ret = do_aux_function(ch_option, pos);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// @LoggerMessage: AUXF
|
// @LoggerMessage: AUXF
|
||||||
// @Description: Auxiliary function invocation information
|
// @Description: Auxiliary function invocation information
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
|
@ -1238,6 +1239,8 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun
|
||||||
uint8_t(source),
|
uint8_t(source),
|
||||||
uint8_t(ret)
|
uint8_t(ret)
|
||||||
);
|
);
|
||||||
|
#endif
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1544,6 +1547,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
case AUX_FUNC::LOG_PAUSE: {
|
case AUX_FUNC::LOG_PAUSE: {
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
switch (ch_flag) {
|
switch (ch_flag) {
|
||||||
|
@ -1559,6 +1563,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if COMPASS_CAL_ENABLED
|
#if COMPASS_CAL_ENABLED
|
||||||
case AUX_FUNC::MAG_CAL: {
|
case AUX_FUNC::MAG_CAL: {
|
||||||
|
|
|
@ -169,10 +169,12 @@ void RC_Channels::read_aux_all()
|
||||||
}
|
}
|
||||||
need_log |= c->read_aux();
|
need_log |= c->read_aux();
|
||||||
}
|
}
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
if (need_log) {
|
if (need_log) {
|
||||||
// guarantee that we log when a switch changes
|
// guarantee that we log when a switch changes
|
||||||
AP::logger().Write_RCIN();
|
AP::logger().Write_RCIN();
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void RC_Channels::init_aux_all()
|
void RC_Channels::init_aux_all()
|
||||||
|
|
Loading…
Reference in New Issue