mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOMCU: remove unnecessary tabs and whitespaces
This commit is contained in:
parent
e90bd27435
commit
12c9e50aef
@ -99,9 +99,9 @@ void AP_IOMCU::thread_main(void)
|
|||||||
uart.begin(1500*1000, 256, 256);
|
uart.begin(1500*1000, 256, 256);
|
||||||
uart.set_blocking_writes(true);
|
uart.set_blocking_writes(true);
|
||||||
uart.set_unbuffered_writes(true);
|
uart.set_unbuffered_writes(true);
|
||||||
|
|
||||||
trigger_event(IOEVENT_INIT);
|
trigger_event(IOEVENT_INIT);
|
||||||
|
|
||||||
while (!do_shutdown) {
|
while (!do_shutdown) {
|
||||||
eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10));
|
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 (mask & EVENT_MASK(IOEVENT_SET_RATES)) {
|
||||||
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) ||
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) ||
|
||||||
!write_register(PAGE_SETUP, PAGE_REG_SETUP_PWM_RATE_MASK, rate.chmask)) {
|
!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,
|
!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0,
|
||||||
P_SETUP_FEATURES_SBUS1_OUT)) {
|
P_SETUP_FEATURES_SBUS1_OUT)) {
|
||||||
event_failed(IOEVENT_ENABLE_SBUS);
|
event_failed(IOEVENT_ENABLE_SBUS);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -195,7 +195,7 @@ void AP_IOMCU::thread_main(void)
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) {
|
if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) {
|
||||||
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) {
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) {
|
||||||
event_failed(IOEVENT_SET_SAFETY_MASK);
|
event_failed(IOEVENT_SET_SAFETY_MASK);
|
||||||
@ -210,7 +210,7 @@ void AP_IOMCU::thread_main(void)
|
|||||||
read_rc_input();
|
read_rc_input();
|
||||||
last_rc_read_ms = AP_HAL::millis();
|
last_rc_read_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (now - last_status_read_ms > 50) {
|
if (now - last_status_read_ms > 50) {
|
||||||
// read status at 20Hz
|
// read status at 20Hz
|
||||||
read_status();
|
read_status();
|
||||||
@ -272,7 +272,7 @@ void AP_IOMCU::send_servo_out()
|
|||||||
last_servo_out_us = now;
|
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;
|
IOPacket pkt;
|
||||||
|
|
||||||
discard_input();
|
discard_input();
|
||||||
|
|
||||||
memset(&pkt.regs[0], 0, count*2);
|
memset(&pkt.regs[0], 0, count*2);
|
||||||
|
|
||||||
pkt.code = CODE_READ;
|
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_size = 4;
|
||||||
}
|
}
|
||||||
|
|
||||||
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size);
|
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size);
|
||||||
|
|
||||||
size_t ret = write_wait((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);
|
AP_HAL::millis(), page, offset, count);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t *b = (uint8_t *)&pkt;
|
uint8_t *b = (uint8_t *)&pkt;
|
||||||
uint8_t n = uart.available();
|
uint8_t n = uart.available();
|
||||||
if (n < offsetof(struct IOPacket, regs)) {
|
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;
|
regs += PKT_MAX_REGS;
|
||||||
}
|
}
|
||||||
IOPacket pkt;
|
IOPacket pkt;
|
||||||
|
|
||||||
discard_input();
|
discard_input();
|
||||||
|
|
||||||
memset(&pkt.regs[0], 0, count*2);
|
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++;
|
protocol_fail_count++;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t *b = (uint8_t *)&pkt;
|
uint8_t *b = (uint8_t *)&pkt;
|
||||||
uint8_t n = uart.available();
|
uint8_t n = uart.available();
|
||||||
for (uint8_t i=0; i<n; i++) {
|
for (uint8_t i=0; i<n; i++) {
|
||||||
@ -757,7 +757,7 @@ bool AP_IOMCU::check_crc(void)
|
|||||||
{
|
{
|
||||||
// flash size minus 4k bootloader
|
// flash size minus 4k bootloader
|
||||||
const uint32_t flash_size = 0x10000 - 0x1000;
|
const uint32_t flash_size = 0x10000 - 0x1000;
|
||||||
|
|
||||||
fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
||||||
if (!fw) {
|
if (!fw) {
|
||||||
hal.console->printf("failed to find %s\n", fw_name);
|
hal.console->printf("failed to find %s\n", fw_name);
|
||||||
@ -796,7 +796,7 @@ bool AP_IOMCU::check_crc(void)
|
|||||||
fw = nullptr;
|
fw = nullptr;
|
||||||
AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
|
AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
free(fw);
|
free(fw);
|
||||||
fw = nullptr;
|
fw = nullptr;
|
||||||
return false;
|
return false;
|
||||||
@ -846,7 +846,7 @@ void AP_IOMCU::set_safety_mask(uint16_t chmask)
|
|||||||
{
|
{
|
||||||
if (pwm_out.safety_mask != chmask) {
|
if (pwm_out.safety_mask != chmask) {
|
||||||
pwm_out.safety_mask = chmask;
|
pwm_out.safety_mask = chmask;
|
||||||
trigger_event(IOEVENT_SET_SAFETY_MASK);
|
trigger_event(IOEVENT_SET_SAFETY_MASK);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -54,7 +54,7 @@ public:
|
|||||||
|
|
||||||
// set PWM of channels when in FMU failsafe
|
// set PWM of channels when in FMU failsafe
|
||||||
void set_failsafe_pwm(uint16_t chmask, uint16_t period_us);
|
void set_failsafe_pwm(uint16_t chmask, uint16_t period_us);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
enable sbus output
|
enable sbus output
|
||||||
*/
|
*/
|
||||||
@ -92,7 +92,7 @@ public:
|
|||||||
|
|
||||||
// set to brushed mode
|
// set to brushed mode
|
||||||
void set_brushed_mode(void);
|
void set_brushed_mode(void);
|
||||||
|
|
||||||
// check if IO is healthy
|
// check if IO is healthy
|
||||||
bool healthy(void);
|
bool healthy(void);
|
||||||
|
|
||||||
@ -102,7 +102,7 @@ public:
|
|||||||
// setup for FMU failsafe mixing
|
// setup for FMU failsafe mixing
|
||||||
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||||
float mixing_gain, uint16_t manual_rc_mask);
|
float mixing_gain, uint16_t manual_rc_mask);
|
||||||
|
|
||||||
// channel group masks
|
// channel group masks
|
||||||
const uint8_t ch_masks[3] = { 0x03,0x0C,0xF0 };
|
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) {
|
bool write_register(uint8_t page, uint8_t offset, uint16_t v) {
|
||||||
return write_registers(page, offset, 1, &v);
|
return write_registers(page, offset, 1, &v);
|
||||||
}
|
}
|
||||||
|
|
||||||
// modify a single register
|
// modify a single register
|
||||||
bool modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits);
|
bool modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits);
|
||||||
|
|
||||||
@ -166,7 +166,7 @@ private:
|
|||||||
|
|
||||||
// MIXER values
|
// MIXER values
|
||||||
struct page_mixing mixing;
|
struct page_mixing mixing;
|
||||||
|
|
||||||
// output pwm values
|
// output pwm values
|
||||||
struct {
|
struct {
|
||||||
uint8_t num_channels;
|
uint8_t num_channels;
|
||||||
|
@ -421,7 +421,7 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
|
|||||||
}
|
}
|
||||||
|
|
||||||
crc_is_ok = true;
|
crc_is_ok = true;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -557,7 +557,7 @@ bool AP_IOMCU_FW::handle_code_write()
|
|||||||
dsm_bind_state = 1;
|
dsm_bind_state = 1;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -749,6 +749,3 @@ void AP_IOMCU_FW::fill_failsafe_pwm(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -112,7 +112,7 @@ public:
|
|||||||
|
|
||||||
// true when override channel active
|
// true when override channel active
|
||||||
bool override_active;
|
bool override_active;
|
||||||
|
|
||||||
// sbus rate handling
|
// sbus rate handling
|
||||||
uint32_t sbus_last_ms;
|
uint32_t sbus_last_ms;
|
||||||
uint32_t sbus_interval_ms;
|
uint32_t sbus_interval_ms;
|
||||||
@ -148,4 +148,3 @@ public:
|
|||||||
#define AMBER_SET(on) palWriteLine(HAL_GPIO_PIN_AMBER_LED, !(on));
|
#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_POWER(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, on);
|
||||||
#define SPEKTRUM_SET(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_OUT, on);
|
#define SPEKTRUM_SET(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_OUT, on);
|
||||||
|
|
||||||
|
@ -158,7 +158,7 @@ void AP_IOMCU_FW::run_mixer(void)
|
|||||||
case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16:
|
case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16:
|
||||||
pwm = rc_input.pwm[(uint8_t)(function - SRV_Channel::k_rcin1)];
|
pwm = rc_input.pwm[(uint8_t)(function - SRV_Channel::k_rcin1)];
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case SRV_Channel::k_aileron:
|
case SRV_Channel::k_aileron:
|
||||||
case SRV_Channel::k_aileron_with_input:
|
case SRV_Channel::k_aileron_with_input:
|
||||||
case SRV_Channel::k_flaperon_left:
|
case SRV_Channel::k_flaperon_left:
|
||||||
@ -213,7 +213,7 @@ void AP_IOMCU_FW::run_mixer(void)
|
|||||||
case SRV_Channel::k_vtail_right:
|
case SRV_Channel::k_vtail_right:
|
||||||
pwm = mix_output_angle(i, mix_elevon_vtail(rudder, pitch, true));
|
pwm = mix_output_angle(i, mix_elevon_vtail(rudder, pitch, true));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -181,4 +181,3 @@ void AP_IOMCU_FW::dsm_bind_step(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user