AP_PiccoloCAN: ESC command rate now configurable

Uses CAN_Dx_PC_ESC_MS parameter to set the ESC data rate (in ms)
This commit is contained in:
Oliver Walters 2020-01-23 14:56:06 +11:00 committed by Andrew Tridgell
parent a98babc02c
commit 17932e3d1d
2 changed files with 16 additions and 7 deletions

View File

@ -151,7 +151,8 @@ void AP_PiccoloCAN::loop()
// How often to transmit CAN messages (milliseconds)
#define CMD_TX_PERIOD 10
uint16_t txCounter = 0;
uint16_t esc_tx_counter = 0;
uint16_t srv_tx_counter = 0;
// CAN Frame ID components
uint8_t frame_id_group; // Piccolo message group
@ -172,14 +173,23 @@ void AP_PiccoloCAN::loop()
// 1ms loop delay
hal.scheduler->delay_microseconds(1 * 1000);
// Transmit CAN commands at regular intervals
if (txCounter++ > CMD_TX_PERIOD) {
// Transmit ESC commands at regular intervals
if (esc_tx_counter++ > _esc_ms) {
esc_tx_counter = 0;
txCounter = 0;
// Transmit ESC commands
if (_esc_ms >= PICCOLO_MSG_RATE_MS_MIN) {
send_esc_messages();
}
}
// Transmit servo commands at regular intervals
if (srv_tx_counter++ > _srv_ms) {
srv_tx_counter = 0;
if (_srv_ms >= PICCOLO_MSG_RATE_MS_MIN) {
// TODO - Transmit servo messages
}
}
// Look for any message responses on the CAN bus
while (read_frame(rxFrame, timeout)) {

View File

@ -36,7 +36,6 @@
#if HAL_PICCOLO_CAN_ENABLE
#define PICCOLO_MSG_RATE_MS_MIN 2
#define PICCOLO_MSG_RATE_MS_MAX 100
#define PICCOLO_MSG_RATE_MS_DEFAULT 20
class AP_PiccoloCAN : public AP_CANDriver