Skip to content

Commit

Permalink
AP_HAL_QURT: Added support for PWM channels 4 to 8 when using the IO …
Browse files Browse the repository at this point in the history
…board
  • Loading branch information
katzfey committed Dec 23, 2024
1 parent 169d6f6 commit daf49ca
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 11 deletions.
12 changes: 4 additions & 8 deletions libraries/AP_HAL_QURT/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ void RCOutput::send_esc_command(void)
// We don't set any LEDs
data[4] = 0;

for (uint8_t i=0; i<channel_count; i++) {
for (uint8_t i=0; i<esc_channel_count; i++) {
data[i] = pwm_to_esc(pwm_output[i]);
// Make sure feedback request bit is cleared for all ESCs
data[i] &= 0xFFFE;
Expand Down Expand Up @@ -186,13 +186,9 @@ void RCOutput::send_io_command(void)

// Resolution of commands in the packet is 0.05us = 50ns
// Convert from standard 1us resolution to IO command resolution
for (uint32_t idx=0; idx<channel_count; idx++) {
for (uint32_t idx=0; idx<io_channel_count; idx++) {
hires_pwm_cmd.vals[idx] = pwm_output[idx] * 20;
}
// Channels 4 - 8 not supported right now
for (uint32_t idx=4; idx<8; idx++) {
hires_pwm_cmd.vals[idx] = 0;
}

send_packet(IO_PACKET_TYPE_PWM_HIRES_CMD, (uint8_t *) &hires_pwm_cmd, sizeof(hires_pwm_cmd));
}
Expand All @@ -207,7 +203,7 @@ void RCOutput::send_pwm_output(void)
safety_mask = boardconfig->get_safety_mask();
}

for (uint8_t i=0; i<channel_count; i++) {
for (uint8_t i=0; i<max_channel_count; i++) {
uint16_t v = period[i];
if (safety_on && (safety_mask & (1U<<i)) == 0) {
// when safety is on we send 0, which allows us to still
Expand Down Expand Up @@ -307,7 +303,7 @@ void RCOutput::handle_version_feedback(const struct extended_version_info &pkt)
void RCOutput::handle_esc_feedback(const struct esc_response_v2 &pkt)
{
const uint8_t idx = pkt.id_state>>4;
if (idx >= ARRAY_SIZE(period)) {
if (idx >= esc_channel_count) {
return;
}
update_rpm(idx, pkt.rpm);
Expand Down
8 changes: 5 additions & 3 deletions libraries/AP_HAL_QURT/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,9 +105,11 @@ class QURT::RCOutput : public AP_HAL::RCOutput, AP_ESC_Telem_Backend

int fd = -1;
uint16_t enable_mask;
static const uint8_t channel_count = 4;
uint16_t period[channel_count];
uint16_t pwm_output[channel_count];
static const uint8_t max_channel_count = 8;
static const uint8_t esc_channel_count = 4;
static const uint8_t io_channel_count = 8;
uint16_t period[max_channel_count];
uint16_t pwm_output[max_channel_count];
volatile bool need_write;
bool corked;
HAL_Semaphore mutex;
Expand Down

0 comments on commit daf49ca

Please sign in to comment.