mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-03-23 18:13:49 +08:00
refactor(msg): remove esc_address from EscReport
This commit is contained in:
committed by
Matthias Grob
parent
aeb71cc8b4
commit
8765275b5d
@@ -5,7 +5,6 @@ int32 esc_rpm # [rpm] Motor RPM, negative for reverse rotation - if supported
|
||||
float32 esc_voltage # [V] Voltage measured from current ESC - if supported
|
||||
float32 esc_current # [A] Current measured from current ESC - if supported
|
||||
float32 esc_temperature # [degC] Temperature measured from current ESC - if supported
|
||||
uint8 esc_address # [-] Address of current ESC (in most cases 1-12 / must be set by driver)
|
||||
int16 motor_temperature # [degC] Temperature measured from current motor - if supported
|
||||
|
||||
uint8 esc_state # [-] State of ESC - depend on Vendor
|
||||
|
||||
@@ -80,7 +80,6 @@ void VertiqTelemetryManager::StartPublishing(uORB::Publication<esc_status_s> *es
|
||||
|
||||
for (unsigned i = 0; i < _number_of_module_ids_for_telem; i++) {
|
||||
_esc_status.esc[i].timestamp = 0;
|
||||
_esc_status.esc[i].esc_address = 0;
|
||||
_esc_status.esc[i].esc_rpm = 0;
|
||||
_esc_status.esc[i].esc_state = 0;
|
||||
_esc_status.esc[i].esc_voltage = 0;
|
||||
@@ -111,7 +110,6 @@ uint16_t VertiqTelemetryManager::UpdateTelemetry()
|
||||
IFCITelemetryData telem_response = _telem_interface.telemetry_.get_reply();
|
||||
|
||||
// also update our internal report for logging
|
||||
_esc_status.esc[_current_module_id_target_index].esc_address = _module_ids_in_use[_number_of_module_ids_for_telem];
|
||||
_esc_status.esc[_current_module_id_target_index].timestamp = time_now;
|
||||
_esc_status.esc[_current_module_id_target_index].esc_rpm = telem_response.speed * 60.0f * M_1_PI_F *
|
||||
0.5f; //We get back rad/s, convert to rpm
|
||||
|
||||
@@ -63,7 +63,6 @@ VoxlEsc::VoxlEsc() :
|
||||
|
||||
for (unsigned i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++) {
|
||||
_esc_status.esc[i].timestamp = 0;
|
||||
_esc_status.esc[i].esc_address = 0;
|
||||
_esc_status.esc[i].esc_rpm = 0;
|
||||
_esc_status.esc[i].esc_state = 0;
|
||||
_esc_status.esc[i].esc_voltage = 0;
|
||||
@@ -520,7 +519,6 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
|
||||
_esc_chans[id].feedback_time = tnow;
|
||||
|
||||
// also update our internal report for logging
|
||||
_esc_status.esc[id].esc_address = motor_idx + 1; //remapped motor ID
|
||||
_esc_status.esc[id].timestamp = tnow;
|
||||
_esc_status.esc[id].esc_rpm = fb.rpm;
|
||||
_esc_status.esc[id].esc_power = fb.power;
|
||||
@@ -559,14 +557,6 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
|
||||
}
|
||||
|
||||
|
||||
//print ESC status just for debugging
|
||||
/*
|
||||
PX4_INFO("[%lld] ID=%d, ADDR %d, STATE=%d, RPM=%5d, PWR=%3d%%, V=%.2fdV, I=%.2fA, T=%+3dC, FAIL %d",
|
||||
_esc_status.esc[id].timestamp, id, _esc_status.esc[id].esc_address,
|
||||
_esc_status.esc[id].esc_state, _esc_status.esc[id].esc_rpm, _esc_status.esc[id].esc_power,
|
||||
(double)_esc_status.esc[id].esc_voltage, (double)_esc_status.esc[id].esc_current, _esc_status.esc[id].esc_temperature,
|
||||
_esc_status.esc[id].failures);
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -243,7 +243,6 @@ public:
|
||||
const ZubaxCompactFeedback *feedback = ((const ZubaxCompactFeedback *)(receive.payload));
|
||||
|
||||
ref.timestamp = hrt_absolute_time();
|
||||
ref.esc_address = receive.metadata.remote_node_id;
|
||||
ref.esc_voltage = 0.2 * feedback->dc_voltage;
|
||||
ref.esc_current = 0.2 * feedback->dc_current;
|
||||
ref.esc_temperature = NAN;
|
||||
|
||||
@@ -115,14 +115,13 @@ void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<
|
||||
if (msg.esc_index < esc_status_s::CONNECTED_ESC_MAX) {
|
||||
esc_report_s &esc_report = _esc_status.esc[msg.esc_index];
|
||||
esc_report.timestamp = hrt_absolute_time();
|
||||
esc_report.esc_address = msg.getSrcNodeID().get();
|
||||
esc_report.esc_voltage = msg.voltage;
|
||||
esc_report.esc_current = msg.current;
|
||||
esc_report.esc_temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius; // Kelvin to Celsius
|
||||
// esc_report.motor_temperature is filled in the extended status callback
|
||||
esc_report.esc_rpm = msg.rpm;
|
||||
esc_report.esc_errorcount = msg.error_count;
|
||||
esc_report.failures = get_failures(msg.esc_index);
|
||||
esc_report.failures = get_failures(msg.esc_index, msg.getSrcNodeID().get());
|
||||
|
||||
_esc_status.esc_count = _rotor_count;
|
||||
_esc_status.counter += 1;
|
||||
@@ -169,11 +168,11 @@ uint16_t UavcanEscController::check_escs_status()
|
||||
return esc_status_flags;
|
||||
}
|
||||
|
||||
uint32_t UavcanEscController::get_failures(uint8_t esc_index)
|
||||
uint32_t UavcanEscController::get_failures(uint8_t esc_index, uint8_t node_id)
|
||||
{
|
||||
// Check DoneCAN node health of the ESC
|
||||
// Check DroneCAN node health of the ESC
|
||||
dronecan_node_status_s node_status{};
|
||||
uint8_t esc_node_id = _esc_status.esc[esc_index].esc_address;
|
||||
uint8_t esc_node_id = node_id;
|
||||
uint8_t node_health = dronecan_node_status_s::HEALTH_OK;
|
||||
uint16_t vendor_specific_status_code = 0;
|
||||
|
||||
|
||||
@@ -104,7 +104,7 @@ private:
|
||||
/**
|
||||
* Gets failure flags for a specific ESC
|
||||
*/
|
||||
uint32_t get_failures(uint8_t esc_index);
|
||||
uint32_t get_failures(uint8_t esc_index, uint8_t node_id);
|
||||
|
||||
typedef uavcan::MethodBinder<UavcanEscController *,
|
||||
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)> StatusCbBinder;
|
||||
|
||||
Reference in New Issue
Block a user