#include "AP_Periph.h"
#if AP_SERVO_TELEM_ENABLED
#include <dronecan_msgs.h>
void AP_Periph_FW::servo_telem_update()
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - servo_telem.last_update_ms > 20) {
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
actuator_telem.update();
#endif
servo_telem.lib.update();
servo_telem.last_update_ms = now_ms;
}
if (g.servo_telem_msg_rate <= 0) {
return;
}
if (now_ms - servo_telem.last_send_ms < (1000U / g.servo_telem_msg_rate)) {
return;
}
servo_telem.last_send_ms = now_ms;
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
const uint8_t index = (servo_telem.last_send_index + 1 + i) % NUM_SERVO_CHANNELS;
AP_Servo_Telem::TelemetryData data;
if (!servo_telem.lib.get_telem(index, data)) {
continue;
}
if (AP_HAL::timeout_expired(data.last_update_ms, now_ms, 5000U)) {
continue;
}
const float nan = nanf("");
uavcan_equipment_actuator_Status pkt {
actuator_id: (uint8_t)(index + 1),
position: nan,
force: nan,
speed: nan,
power_rating_pct: UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN
};
if (data.present(AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION)) {
pkt.position = radians(data.measured_position);
}
if (data.present(AP_Servo_Telem::TelemetryData::Types::FORCE)) {
pkt.force = data.force;
}
if (data.present(AP_Servo_Telem::TelemetryData::Types::SPEED)) {
pkt.speed = data.speed;
}
if (data.present(AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE)) {
pkt.power_rating_pct = data.duty_cycle;
}
uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];
const uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !canfdout());
canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,
UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer[0],
total_size);
servo_telem.last_send_index = index;
break;
}
}
#endif