From 12c9e50aefbb09de706deaf94480d04f1d2b2507 Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Sun, 20 Oct 2019 15:47:14 +0200 Subject: [PATCH] AP_IOMCU: remove unnecessary tabs and whitespaces --- libraries/AP_IOMCU/AP_IOMCU.cpp | 30 ++++++++++---------- libraries/AP_IOMCU/AP_IOMCU.h | 10 +++---- libraries/AP_IOMCU/fw_uploader.cpp | 2 +- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 5 +--- libraries/AP_IOMCU/iofirmware/iofirmware.h | 3 +- libraries/AP_IOMCU/iofirmware/mixer.cpp | 4 +-- libraries/AP_IOMCU/iofirmware/rc.cpp | 1 - 7 files changed, 25 insertions(+), 30 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 021fa153f6..a01cd33316 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -99,9 +99,9 @@ void AP_IOMCU::thread_main(void) uart.begin(1500*1000, 256, 256); uart.set_blocking_writes(true); uart.set_unbuffered_writes(true); - + trigger_event(IOEVENT_INIT); - + while (!do_shutdown) { eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10)); @@ -150,7 +150,7 @@ void AP_IOMCU::thread_main(void) } } - + if (mask & EVENT_MASK(IOEVENT_SET_RATES)) { if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) || !write_register(PAGE_SETUP, PAGE_REG_SETUP_PWM_RATE_MASK, rate.chmask)) { @@ -164,7 +164,7 @@ void AP_IOMCU::thread_main(void) !modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_SBUS1_OUT)) { event_failed(IOEVENT_ENABLE_SBUS); - continue; + continue; } } @@ -195,7 +195,7 @@ void AP_IOMCU::thread_main(void) continue; } } - + if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) { if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) { event_failed(IOEVENT_SET_SAFETY_MASK); @@ -210,7 +210,7 @@ void AP_IOMCU::thread_main(void) read_rc_input(); last_rc_read_ms = AP_HAL::millis(); } - + if (now - last_status_read_ms > 50) { // read status at 20Hz read_status(); @@ -272,7 +272,7 @@ void AP_IOMCU::send_servo_out() last_servo_out_us = now; } } - } + } } /* @@ -408,7 +408,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 IOPacket pkt; discard_input(); - + memset(&pkt.regs[0], 0, count*2); pkt.code = CODE_READ; @@ -428,7 +428,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 */ pkt_size = 4; } - + pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size); size_t ret = write_wait((uint8_t *)&pkt, pkt_size); @@ -445,7 +445,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 AP_HAL::millis(), page, offset, count); return false; } - + uint8_t *b = (uint8_t *)&pkt; uint8_t n = uart.available(); if (n < offsetof(struct IOPacket, regs)) { @@ -509,7 +509,7 @@ bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, cons regs += PKT_MAX_REGS; } IOPacket pkt; - + discard_input(); memset(&pkt.regs[0], 0, count*2); @@ -537,7 +537,7 @@ bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, cons protocol_fail_count++; return false; } - + uint8_t *b = (uint8_t *)&pkt; uint8_t n = uart.available(); for (uint8_t i=0; iprintf("failed to find %s\n", fw_name); @@ -796,7 +796,7 @@ bool AP_IOMCU::check_crc(void) fw = nullptr; AP_BoardConfig::sensor_config_error("Failed to update IO firmware"); } - + free(fw); fw = nullptr; return false; @@ -846,7 +846,7 @@ void AP_IOMCU::set_safety_mask(uint16_t chmask) { if (pwm_out.safety_mask != chmask) { pwm_out.safety_mask = chmask; - trigger_event(IOEVENT_SET_SAFETY_MASK); + trigger_event(IOEVENT_SET_SAFETY_MASK); } } diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index e6fffc58ac..c02721061e 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -54,7 +54,7 @@ public: // set PWM of channels when in FMU failsafe void set_failsafe_pwm(uint16_t chmask, uint16_t period_us); - + /* enable sbus output */ @@ -92,7 +92,7 @@ public: // set to brushed mode void set_brushed_mode(void); - + // check if IO is healthy bool healthy(void); @@ -102,7 +102,7 @@ public: // setup for FMU failsafe mixing bool setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask); - + // channel group masks const uint8_t ch_masks[3] = { 0x03,0x0C,0xF0 }; @@ -121,7 +121,7 @@ private: bool write_register(uint8_t page, uint8_t offset, uint16_t v) { return write_registers(page, offset, 1, &v); } - + // modify a single register bool modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits); @@ -166,7 +166,7 @@ private: // MIXER values struct page_mixing mixing; - + // output pwm values struct { uint8_t num_channels; diff --git a/libraries/AP_IOMCU/fw_uploader.cpp b/libraries/AP_IOMCU/fw_uploader.cpp index b2d344c202..b2c14f7b8c 100644 --- a/libraries/AP_IOMCU/fw_uploader.cpp +++ b/libraries/AP_IOMCU/fw_uploader.cpp @@ -421,7 +421,7 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local) } crc_is_ok = true; - + return true; } diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 606faf1bd2..049ec5905a 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -557,7 +557,7 @@ bool AP_IOMCU_FW::handle_code_write() dsm_bind_state = 1; } break; - + default: break; } @@ -749,6 +749,3 @@ void AP_IOMCU_FW::fill_failsafe_pwm(void) } AP_HAL_MAIN(); - - - diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.h b/libraries/AP_IOMCU/iofirmware/iofirmware.h index 8bf1c156ed..0a45c6f37f 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.h +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.h @@ -112,7 +112,7 @@ public: // true when override channel active bool override_active; - + // sbus rate handling uint32_t sbus_last_ms; uint32_t sbus_interval_ms; @@ -148,4 +148,3 @@ public: #define AMBER_SET(on) palWriteLine(HAL_GPIO_PIN_AMBER_LED, !(on)); #define SPEKTRUM_POWER(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, on); #define SPEKTRUM_SET(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_OUT, on); - diff --git a/libraries/AP_IOMCU/iofirmware/mixer.cpp b/libraries/AP_IOMCU/iofirmware/mixer.cpp index b1a6f51905..9f270704b0 100644 --- a/libraries/AP_IOMCU/iofirmware/mixer.cpp +++ b/libraries/AP_IOMCU/iofirmware/mixer.cpp @@ -158,7 +158,7 @@ void AP_IOMCU_FW::run_mixer(void) case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16: pwm = rc_input.pwm[(uint8_t)(function - SRV_Channel::k_rcin1)]; break; - + case SRV_Channel::k_aileron: case SRV_Channel::k_aileron_with_input: case SRV_Channel::k_flaperon_left: @@ -213,7 +213,7 @@ void AP_IOMCU_FW::run_mixer(void) case SRV_Channel::k_vtail_right: pwm = mix_output_angle(i, mix_elevon_vtail(rudder, pitch, true)); break; - + default: break; } diff --git a/libraries/AP_IOMCU/iofirmware/rc.cpp b/libraries/AP_IOMCU/iofirmware/rc.cpp index e3d373639c..20d08e19ce 100644 --- a/libraries/AP_IOMCU/iofirmware/rc.cpp +++ b/libraries/AP_IOMCU/iofirmware/rc.cpp @@ -181,4 +181,3 @@ void AP_IOMCU_FW::dsm_bind_step(void) break; } } -