Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/Servo_telem.cpp
13808 views
1
2
#include "AP_Periph.h"
3
4
#if AP_SERVO_TELEM_ENABLED
5
6
#include <dronecan_msgs.h>
7
8
// Send servo telem message occasionally
9
void AP_Periph_FW::servo_telem_update()
10
{
11
const uint32_t now_ms = AP_HAL::millis();
12
13
// Run update function at 50hz mirroring vehicle update rate
14
if (now_ms - servo_telem.last_update_ms > 20) {
15
// Update periph only actuator telem
16
#if AP_PERIPH_ACTUATOR_TELEM_ENABLED
17
actuator_telem.update();
18
#endif
19
20
// Update main servo telem lib
21
servo_telem.lib.update();
22
servo_telem.last_update_ms = now_ms;
23
}
24
25
// Reporting is disabled
26
if (g.servo_telem_msg_rate <= 0) {
27
return;
28
}
29
30
// Check if its time to send the next instance
31
if (now_ms - servo_telem.last_send_ms < (1000U / g.servo_telem_msg_rate)) {
32
return;
33
}
34
servo_telem.last_send_ms = now_ms;
35
36
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
37
// Send each servo in turn
38
const uint8_t index = (servo_telem.last_send_index + 1 + i) % NUM_SERVO_CHANNELS;
39
40
// Move on to next instance if no data is available
41
AP_Servo_Telem::TelemetryData data;
42
if (!servo_telem.lib.get_telem(index, data)) {
43
continue;
44
}
45
46
// Don't send stale data, timeout after five seconds
47
if (AP_HAL::timeout_expired(data.last_update_ms, now_ms, 5000U)) {
48
continue;
49
}
50
51
// Blank packet
52
const float nan = nanf("");
53
uavcan_equipment_actuator_Status pkt {
54
actuator_id: (uint8_t)(index + 1), // One based indexing for DroneCAN transport
55
position: nan,
56
force: nan,
57
speed: nan,
58
power_rating_pct: UAVCAN_EQUIPMENT_ACTUATOR_STATUS_POWER_RATING_PCT_UNKNOWN
59
};
60
61
// Fill in present data
62
if (data.present(AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION)) {
63
pkt.position = radians(data.measured_position);
64
}
65
if (data.present(AP_Servo_Telem::TelemetryData::Types::FORCE)) {
66
pkt.force = data.force;
67
}
68
if (data.present(AP_Servo_Telem::TelemetryData::Types::SPEED)) {
69
pkt.speed = data.speed;
70
}
71
if (data.present(AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE)) {
72
pkt.power_rating_pct = data.duty_cycle;
73
}
74
75
// Encode message into buffer
76
uint8_t buffer[UAVCAN_EQUIPMENT_ACTUATOR_STATUS_MAX_SIZE];
77
const uint16_t total_size = uavcan_equipment_actuator_Status_encode(&pkt, buffer, !canfdout());
78
79
// Send message
80
canard_broadcast(UAVCAN_EQUIPMENT_ACTUATOR_STATUS_SIGNATURE,
81
UAVCAN_EQUIPMENT_ACTUATOR_STATUS_ID,
82
CANARD_TRANSFER_PRIORITY_LOW,
83
&buffer[0],
84
total_size);
85
86
servo_telem.last_send_index = index;
87
break;
88
}
89
}
90
91
#endif // AP_SERVO_TELEM_ENABLED
92
93