mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: actuator status is measured, not commanded
This commit is contained in:
parent
13807f24d7
commit
bf5555ccd3
|
@ -1393,7 +1393,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
|
|||
.force = msg.force,
|
||||
.speed = msg.speed,
|
||||
.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::SPEED |
|
||||
AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE
|
||||
|
|
Loading…
Reference in New Issue