AP_Torqeedo: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
573a7b172e
commit
6c10b38442
@ -564,6 +564,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
esc_temp,
|
esc_temp,
|
||||||
motor_temp);
|
motor_temp);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log data
|
// log data
|
||||||
if ((_options & options::LOG) != 0) {
|
if ((_options & options::LOG) != 0) {
|
||||||
// @LoggerMessage: TRST
|
// @LoggerMessage: TRST
|
||||||
@ -592,6 +593,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_display_system_state.batt_voltage,
|
_display_system_state.batt_voltage,
|
||||||
_display_system_state.batt_current);
|
_display_system_state.batt_current);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send to GCS
|
// send to GCS
|
||||||
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
||||||
@ -625,6 +627,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_display_system_setup.batt_type = _received_buff[9];
|
_display_system_setup.batt_type = _received_buff[9];
|
||||||
_display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]);
|
_display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log data
|
// log data
|
||||||
if ((_options & options::LOG) != 0) {
|
if ((_options & options::LOG) != 0) {
|
||||||
// @LoggerMessage: TRSE
|
// @LoggerMessage: TRSE
|
||||||
@ -647,6 +650,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_display_system_setup.batt_type,
|
_display_system_setup.batt_type,
|
||||||
_display_system_setup.master_sw_version);
|
_display_system_setup.master_sw_version);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send to GCS
|
// send to GCS
|
||||||
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
||||||
@ -694,6 +698,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_motor_param.pcb_temp, // esc temp
|
_motor_param.pcb_temp, // esc temp
|
||||||
_motor_param.stator_temp); // motor temp
|
_motor_param.stator_temp); // motor temp
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log data
|
// log data
|
||||||
if ((_options & options::LOG) != 0) {
|
if ((_options & options::LOG) != 0) {
|
||||||
// @LoggerMessage: TRMP
|
// @LoggerMessage: TRMP
|
||||||
@ -714,6 +719,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_motor_param.pcb_temp,
|
_motor_param.pcb_temp,
|
||||||
_motor_param.stator_temp);
|
_motor_param.stator_temp);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send to GCS
|
// send to GCS
|
||||||
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
||||||
@ -736,6 +742,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_motor_status.status_flags_value = _received_buff[2];
|
_motor_status.status_flags_value = _received_buff[2];
|
||||||
_motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]);
|
_motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log data
|
// log data
|
||||||
if ((_options & options::LOG) != 0) {
|
if ((_options & options::LOG) != 0) {
|
||||||
// @LoggerMessage: TRMS
|
// @LoggerMessage: TRMS
|
||||||
@ -748,6 +755,7 @@ void AP_Torqeedo::parse_message()
|
|||||||
_motor_status.status_flags_value,
|
_motor_status.status_flags_value,
|
||||||
_motor_status.error_flags_value);
|
_motor_status.error_flags_value);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// send to GCS
|
// send to GCS
|
||||||
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
||||||
@ -1084,6 +1092,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging)
|
|||||||
const bool health = healthy();
|
const bool health = healthy();
|
||||||
int16_t actual_motor_speed = get_motor_speed_limited();
|
int16_t actual_motor_speed = get_motor_speed_limited();
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
if ((_options & options::LOG) != 0) {
|
if ((_options & options::LOG) != 0) {
|
||||||
// @LoggerMessage: TRQD
|
// @LoggerMessage: TRQD
|
||||||
// @Description: Torqeedo Status
|
// @Description: Torqeedo Status
|
||||||
@ -1101,6 +1110,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging)
|
|||||||
_parse_success_count,
|
_parse_success_count,
|
||||||
_parse_error_count);
|
_parse_error_count);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
if ((_options & options::DEBUG_TO_GCS) != 0) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld",
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld",
|
||||||
|
Loading…
Reference in New Issue
Block a user