AP_DroneCAN: correct narrowing-conversion errors

This commit is contained in:
Peter Barker 2025-01-01 14:02:40 +11:00 committed by Thomas Watson
parent d6e0411e0d
commit e1fd90bc6c

View File

@ -1447,8 +1447,8 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer,
.measured_position = ToDeg(msg.actual_position), .measured_position = ToDeg(msg.actual_position),
.voltage = msg.voltage * 0.2, .voltage = msg.voltage * 0.2,
.current = msg.current * 0.025, .current = msg.current * 0.025,
.duty_cycle = msg.motor_pwm * (100.0/255.0), .duty_cycle = uint8_t(msg.motor_pwm * (100.0/255.0)),
.motor_temperature_cdeg = (int16_t(msg.motor_temperature) - 50) * 100, .motor_temperature_cdeg = int16_t((msg.motor_temperature - 50) * 100),
.valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION | .valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::VOLTAGE | AP_Servo_Telem::TelemetryData::Types::VOLTAGE |
AP_Servo_Telem::TelemetryData::Types::CURRENT | AP_Servo_Telem::TelemetryData::Types::CURRENT |