AP_PiccoloCAN: Update code to match new esc telemetry / logging architecture

This commit is contained in:
Oliver 2021-06-04 17:17:30 +10:00 committed by Andrew Tridgell
parent de3c4cc9da
commit 06eb844ede
1 changed files with 5 additions and 21 deletions

View File

@ -345,24 +345,6 @@ void AP_PiccoloCAN::update()
servo.newTelemetry = false; servo.newTelemetry = false;
} }
} }
for (uint8_t i = 0; i < PICCOLO_CAN_MAX_NUM_ESC; i++) {
PiccoloESC_Info_t &esc = _esc_info[i];
if (esc.newTelemetry) {
logger->Write_ESC(i, timestamp,
(int32_t) esc.rpm * 100,
esc.voltage,
esc.current,
(int16_t) esc.fetTemperature,
0, // TODO - Accumulated current
(int16_t) esc.motorTemperature);
esc.newTelemetry = false;
}
}
} }
} }
@ -707,11 +689,13 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
// There are no common error bits between the Gen-1 and Gen-2 ICD // There are no common error bits between the Gen-1 and Gen-2 ICD
} else if (decodeESC_StatusBPacket(&frame, &esc.voltage, &esc.current, &esc.dutyCycle, &esc.escTemperature, &esc.motorTemperature)) { } else if (decodeESC_StatusBPacket(&frame, &esc.voltage, &esc.current, &esc.dutyCycle, &esc.escTemperature, &esc.motorTemperature)) {
TelemetryData t {
AP_ESC_Telem_Backend::TelemetryData t {
.temperature_cdeg = int16_t(esc.escTemperature * 100), .temperature_cdeg = int16_t(esc.escTemperature * 100),
.voltage = float(esc.voltage) * 0.01f, .voltage = float(esc.voltage) * 0.01f,
.current = float(esc.current) * 0.01f, .current = float(esc.current) * 0.01f,
}; };
update_telem_data(addr, t, update_telem_data(addr, t,
AP_ESC_Telem_Backend::TelemetryType::CURRENT AP_ESC_Telem_Backend::TelemetryType::CURRENT
| AP_ESC_Telem_Backend::TelemetryType::VOLTAGE | AP_ESC_Telem_Backend::TelemetryType::VOLTAGE
@ -719,7 +703,7 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame)
esc.newTelemetry = true; esc.newTelemetry = true;
} else if (decodeESC_StatusCPacket(&frame, &esc.fetTemperature, &esc.pwmFrequency, &esc.timingAdvance)) { } else if (decodeESC_StatusCPacket(&frame, &esc.fetTemperature, &esc.pwmFrequency, &esc.timingAdvance)) {
TelemetryData t { }; AP_ESC_Telem_Backend::TelemetryData t { };
t.motor_temp_cdeg = int16_t(esc.fetTemperature * 100); t.motor_temp_cdeg = int16_t(esc.fetTemperature * 100);
update_telem_data(addr, t, AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE); update_telem_data(addr, t, AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE);
@ -823,7 +807,7 @@ bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint64_t timeout_ms)
/** /**
* Determine if an ESC is present on the CAN bus (has telemetry data been received) * Determine if an ESC is present on the CAN bus (has telemetry data been received)
*/ */
bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms) const bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms)
{ {
if (chan >= PICCOLO_CAN_MAX_NUM_ESC) { if (chan >= PICCOLO_CAN_MAX_NUM_ESC) {
return false; return false;