Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/rpm.cpp
Views: 1798
#include "AP_Periph.h"12#ifdef HAL_PERIPH_ENABLE_RPM_STREAM34#include <dronecan_msgs.h>56// Send rpm message occasionally7void AP_Periph_FW::rpm_sensor_send(void)8{9if (g.rpm_msg_rate <= 0) {10return;11}1213const uint32_t now_ms = AP_HAL::millis();14if (now_ms - rpm_last_send_ms < (1000U / g.rpm_msg_rate)) {15return;16}17rpm_last_send_ms = now_ms;1819{20const uint8_t num_sensors = rpm_sensor.num_sensors();21for (uint8_t i = 0; i < num_sensors; i++) {22// Send each sensor in turn23const uint8_t index = (rpm_last_sent_index + 1 + i) % num_sensors;2425const int8_t sensor_id = rpm_sensor.get_dronecan_sensor_id(index);26if (sensor_id < 0) {27// disabled or not configured to send28continue;29}3031dronecan_sensors_rpm_RPM pkt {};32pkt.sensor_id = sensor_id;3334// Get rpm and set health flag35if (!rpm_sensor.get_rpm(index, pkt.rpm)) {36pkt.flags |= DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY;37}3839uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE];40const uint16_t total_size = dronecan_sensors_rpm_RPM_encode(&pkt, buffer, !canfdout());4142canard_broadcast(DRONECAN_SENSORS_RPM_RPM_SIGNATURE,43DRONECAN_SENSORS_RPM_RPM_ID,44CANARD_TRANSFER_PRIORITY_LOW,45&buffer[0],46total_size);4748rpm_last_sent_index = index;49break;50}51}52}5354#endif // HAL_PERIPH_ENABLE_RPM_STREAM555657