AP_Torqeedo: allow build for periph

This commit is contained in:
Andrew Tridgell 2023-08-18 07:54:39 +10:00 committed by Peter Barker
parent 9665959e84
commit 2380849b4d
1 changed files with 20 additions and 19 deletions

View File

@ -22,6 +22,7 @@
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_SerialManager/AP_SerialManager.h>
#define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200
#define TORQEEDO_PACKET_HEADER 0xAC // communication packet header
@ -345,24 +346,24 @@ void AP_Torqeedo::report_error_codes()
// report display system errors
const char* msg_prefix = "Torqeedo:";
if (_display_system_state.flags.set_throttle_stop) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix);
}
if (_display_system_state.flags.temp_warning) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix);
}
if (_display_system_state.flags.temp_warning) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix);
}
if (_display_system_state.master_error_code > 0) {
const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code);
if (error_string != nullptr) {
gcs().send_text(
GCS_SEND_TEXT(
MAV_SEVERITY_CRITICAL, "%s err:%u %s",
msg_prefix,
_display_system_state.master_error_code,
error_string);
} else {
gcs().send_text(
GCS_SEND_TEXT(
MAV_SEVERITY_CRITICAL, "%s err:%u",
msg_prefix,
_display_system_state.master_error_code);
@ -371,28 +372,28 @@ void AP_Torqeedo::report_error_codes()
// report motor status errors
if (_motor_status.error_flags.overcurrent) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix);
}
if (_motor_status.error_flags.blocked) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix);
}
if (_motor_status.error_flags.overvoltage_static || _motor_status.error_flags.overvoltage_current) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix);
}
if (_motor_status.error_flags.undervoltage_static || _motor_status.error_flags.undervoltage_current) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix);
}
if (_motor_status.error_flags.overtemp_motor || _motor_status.error_flags.overtemp_pcb) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix);
}
if (_motor_status.error_flags.timeout_rs485) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix);
}
if (_motor_status.error_flags.temp_sensor_error) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix);
}
if (_motor_status.error_flags.tilt) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix);
}
// display OK if all errors cleared
@ -405,7 +406,7 @@ void AP_Torqeedo::report_error_codes()
(_motor_status.error_flags_value != 0);
if (!now_errored && prev_errored) {
gcs().send_text(MAV_SEVERITY_INFO, "%s OK", msg_prefix);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix);
}
// record change in state and reporting time
@ -594,7 +595,7 @@ void AP_Torqeedo::parse_message()
// send to GCS
if ((_options & options::DEBUG_TO_GCS) != 0) {
gcs().send_text(MAV_SEVERITY_INFO,"TRST F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f",
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRST F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f",
(unsigned)_display_system_state.flags.value,
(unsigned)_display_system_state.master_error_code,
(double)_display_system_state.motor_voltage,
@ -649,7 +650,7 @@ void AP_Torqeedo::parse_message()
// send to GCS
if ((_options & options::DEBUG_TO_GCS) != 0) {
gcs().send_text(MAV_SEVERITY_INFO,"TRSE:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%",
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRSE:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%",
(unsigned)_display_system_setup.master_sw_version,
(unsigned)_display_system_setup.flags,
(unsigned)_display_system_setup.motor_type,
@ -716,7 +717,7 @@ void AP_Torqeedo::parse_message()
// send to GCS
if ((_options & options::DEBUG_TO_GCS) != 0) {
gcs().send_text(MAV_SEVERITY_INFO, "TRMP: rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f",
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRMP: rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f",
(int)_motor_param.rpm,
(unsigned)_motor_param.power,
(double)_motor_param.voltage,
@ -750,7 +751,7 @@ void AP_Torqeedo::parse_message()
// send to GCS
if ((_options & options::DEBUG_TO_GCS) != 0) {
gcs().send_text(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d",
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d",
_motor_status.status_flags_value,
_motor_status.error_flags_value);
}
@ -1102,7 +1103,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging)
}
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",
(unsigned)health,
(int)_motor_speed_desired,
(int)actual_motor_speed,