From e1fd90bc6c31ed2fa37738013dac253c628040a7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Jan 2025 14:02:40 +1100 Subject: [PATCH] AP_DroneCAN: correct narrowing-conversion errors --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 6895a116bd..5ff651a262 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -1447,8 +1447,8 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, .measured_position = ToDeg(msg.actual_position), .voltage = msg.voltage * 0.2, .current = msg.current * 0.025, - .duty_cycle = msg.motor_pwm * (100.0/255.0), - .motor_temperature_cdeg = (int16_t(msg.motor_temperature) - 50) * 100, + .duty_cycle = uint8_t(msg.motor_pwm * (100.0/255.0)), + .motor_temperature_cdeg = int16_t((msg.motor_temperature - 50) * 100), .valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION | AP_Servo_Telem::TelemetryData::Types::VOLTAGE | AP_Servo_Telem::TelemetryData::Types::CURRENT |