AP_DroneCAN: actuator status is measured, not commanded

This commit is contained in:
Andrew Tridgell 2024-11-19 08:19:37 +11:00
parent 13807f24d7
commit bf5555ccd3
1 changed files with 1 additions and 1 deletions

View File

@ -1393,7 +1393,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
.force = msg.force, .force = msg.force,
.speed = msg.speed, .speed = msg.speed,
.duty_cycle = msg.power_rating_pct, .duty_cycle = msg.power_rating_pct,
.valid_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION | .valid_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |
AP_Servo_Telem::TelemetryData::Types::FORCE | AP_Servo_Telem::TelemetryData::Types::FORCE |
AP_Servo_Telem::TelemetryData::Types::SPEED | AP_Servo_Telem::TelemetryData::Types::SPEED |
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE