CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/AP_Periph/rpm.cpp
Views: 1798
1
#include "AP_Periph.h"
2
3
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
4
5
#include <dronecan_msgs.h>
6
7
// Send rpm message occasionally
8
void AP_Periph_FW::rpm_sensor_send(void)
9
{
10
if (g.rpm_msg_rate <= 0) {
11
return;
12
}
13
14
const uint32_t now_ms = AP_HAL::millis();
15
if (now_ms - rpm_last_send_ms < (1000U / g.rpm_msg_rate)) {
16
return;
17
}
18
rpm_last_send_ms = now_ms;
19
20
{
21
const uint8_t num_sensors = rpm_sensor.num_sensors();
22
for (uint8_t i = 0; i < num_sensors; i++) {
23
// Send each sensor in turn
24
const uint8_t index = (rpm_last_sent_index + 1 + i) % num_sensors;
25
26
const int8_t sensor_id = rpm_sensor.get_dronecan_sensor_id(index);
27
if (sensor_id < 0) {
28
// disabled or not configured to send
29
continue;
30
}
31
32
dronecan_sensors_rpm_RPM pkt {};
33
pkt.sensor_id = sensor_id;
34
35
// Get rpm and set health flag
36
if (!rpm_sensor.get_rpm(index, pkt.rpm)) {
37
pkt.flags |= DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY;
38
}
39
40
uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE];
41
const uint16_t total_size = dronecan_sensors_rpm_RPM_encode(&pkt, buffer, !canfdout());
42
43
canard_broadcast(DRONECAN_SENSORS_RPM_RPM_SIGNATURE,
44
DRONECAN_SENSORS_RPM_RPM_ID,
45
CANARD_TRANSFER_PRIORITY_LOW,
46
&buffer[0],
47
total_size);
48
49
rpm_last_sent_index = index;
50
break;
51
}
52
}
53
}
54
55
#endif // HAL_PERIPH_ENABLE_RPM_STREAM
56
57