Skip to content

Commit

Permalink
AP_DroneCAN: correct narrowing-conversion errors
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and tpwrules committed Jan 1, 2025
1 parent d6e0411 commit e1fd90b
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 |
Expand Down

0 comments on commit e1fd90b

Please sign in to comment.