AP_HAL_ChibiOS: remove unnecessary tabs and whitespaces

This commit is contained in:
Mirko Denecke 2019-10-20 15:31:12 +02:00 committed by Andrew Tridgell
parent 12c9e50aef
commit b84dcd483d
41 changed files with 211 additions and 224 deletions

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -58,7 +58,7 @@ using namespace ChibiOS;
/* /*
scaling table between ADC count and actual input voltage, to account scaling table between ADC count and actual input voltage, to account
for voltage dividers on the board. for voltage dividers on the board.
*/ */
const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS; const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
@ -81,7 +81,7 @@ AnalogSource::AnalogSource(int16_t pin, float initial_value) :
} }
float AnalogSource::read_average() float AnalogSource::read_average()
{ {
WITH_SEMAPHORE(_semaphore); WITH_SEMAPHORE(_semaphore);
@ -97,7 +97,7 @@ float AnalogSource::read_average()
return _value; return _value;
} }
float AnalogSource::read_latest() float AnalogSource::read_latest()
{ {
return _latest_value; return _latest_value;
} }
@ -192,7 +192,7 @@ void AnalogIn::adccallback(ADCDriver *adcp)
stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS); stm32_cacheBufferInvalidate(buffer, sizeof(adcsample_t)*ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS);
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) { for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) { for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
sample_sum[j] += *buffer++; sample_sum[j] += *buffer++;
} }
} }
@ -290,7 +290,7 @@ void AnalogIn::_timer_tick(void)
// update power status flags // update power status flags
update_power_flags(); update_power_flags();
// match the incoming channels to the currently active pins // match the incoming channels to the currently active pins
for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) { for (uint8_t i=0; i < ADC_GRP1_NUM_CHANNELS; i++) {
#ifdef ANALOG_VCC_5V_PIN #ifdef ANALOG_VCC_5V_PIN
@ -312,7 +312,7 @@ void AnalogIn::_timer_tick(void)
_servorail_voltage = iomcu.get_vservo(); _servorail_voltage = iomcu.get_vservo();
_rssi_voltage = iomcu.get_vrssi(); _rssi_voltage = iomcu.get_vrssi();
#endif #endif
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) { for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
Debug("chan %u value=%u\n", Debug("chan %u value=%u\n",
(unsigned)pin_config[i].channel, (unsigned)pin_config[i].channel,
@ -347,7 +347,7 @@ void AnalogIn::_timer_tick(void)
#endif #endif
} }
AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin)
{ {
for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) { for (uint8_t j=0; j<ANALOG_MAX_CHANNELS; j++) {
if (_channels[j] == nullptr) { if (_channels[j] == nullptr) {
@ -371,7 +371,7 @@ void AnalogIn::update_power_flags(void)
flags |= MAV_POWER_STATUS_BRICK_VALID; flags |= MAV_POWER_STATUS_BRICK_VALID;
} }
#endif #endif
#ifdef HAL_GPIO_PIN_VDD_SERVO_VALID #ifdef HAL_GPIO_PIN_VDD_SERVO_VALID
if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) { if (!palReadLine(HAL_GPIO_PIN_VDD_SERVO_VALID)) {
flags |= MAV_POWER_STATUS_SERVO_VALID; flags |= MAV_POWER_STATUS_SERVO_VALID;
@ -392,20 +392,20 @@ void AnalogIn::update_power_flags(void)
flags |= MAV_POWER_STATUS_USB_CONNECTED; flags |= MAV_POWER_STATUS_USB_CONNECTED;
} }
#endif #endif
#ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC #ifdef HAL_GPIO_PIN_VDD_5V_HIPOWER_OC
if (!palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)) { if (!palReadLine(HAL_GPIO_PIN_VDD_5V_HIPOWER_OC)) {
flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT; flags |= MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT;
} }
#endif #endif
#ifdef HAL_GPIO_PIN_VDD_5V_PERIPH_OC #ifdef HAL_GPIO_PIN_VDD_5V_PERIPH_OC
if (!palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)) { if (!palReadLine(HAL_GPIO_PIN_VDD_5V_PERIPH_OC)) {
flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT; flags |= MAV_POWER_STATUS_PERIPH_OVERCURRENT;
} }
#endif #endif
if (_power_flags != 0 && if (_power_flags != 0 &&
_power_flags != flags && _power_flags != flags &&
hal.util->get_soft_armed()) { hal.util->get_soft_armed()) {
// the power status has changed while armed // the power status has changed while armed
flags |= MAV_POWER_STATUS_CHANGED; flags |= MAV_POWER_STATUS_CHANGED;
@ -413,4 +413,3 @@ void AnalogIn::update_power_flags(void)
_power_flags = flags; _power_flags = flags;
} }
#endif // HAL_USE_ADC #endif // HAL_USE_ADC

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
@ -54,7 +54,7 @@ private:
class ChibiOS::AnalogIn : public AP_HAL::AnalogIn { class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {
public: public:
friend class AnalogSource; friend class AnalogSource;
void init() override; void init() override;
AP_HAL::AnalogSource* channel(int16_t pin) override; AP_HAL::AnalogSource* channel(int16_t pin) override;
void _timer_tick(void); void _timer_tick(void);
@ -66,7 +66,7 @@ public:
private: private:
void read_adc(uint32_t *val); void read_adc(uint32_t *val);
void update_power_flags(void); void update_power_flags(void);
int _battery_handle; int _battery_handle;
int _servorail_handle; int _servorail_handle;
int _system_power_handle; int _system_power_handle;
@ -84,9 +84,9 @@ private:
struct pin_info { struct pin_info {
uint8_t channel; uint8_t channel;
float scaling; float scaling;
}; };
static const pin_info pin_config[]; static const pin_info pin_config[];
static adcsample_t *samples; static adcsample_t *samples;
static uint32_t sample_sum[]; static uint32_t sample_sum[];
static uint32_t sample_count; static uint32_t sample_count;

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */

View File

@ -409,4 +409,4 @@ UAVCAN_STM32_IRQ_HANDLER(TIMX_IRQHandler)
} }
#endif #endif
#endif //HAL_WITH_UAVCAN #endif //HAL_WITH_UAVCAN

View File

@ -66,4 +66,3 @@ public:
}; };
#endif // AP_UAVCAN_SLCAN_ENABLED #endif // AP_UAVCAN_SLCAN_ENABLED

View File

@ -1,18 +1,18 @@
/* /*
* The MIT License (MIT) * The MIT License (MIT)
* *
* Copyright (c) 2014 Pavel Kirienko * Copyright (c) 2014 Pavel Kirienko
* *
* Permission is hereby granted, free of charge, to any person obtaining a copy of * Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in * this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to * the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so, * the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions: * subject to the following conditions:
* *
* The above copyright notice and this permission notice shall be included in all * The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. * copies or substantial portions of the Software.
* *
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
@ -34,7 +34,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Siddharth Bharat Purohit * Code by Siddharth Bharat Purohit
*/ */

View File

@ -42,7 +42,7 @@ public:
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len, void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
uint8_t *&buf_rx, uint16_t rx_len); uint8_t *&buf_rx, uint16_t rx_len);
void bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len); void bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len);
private: private:
struct callback_info { struct callback_info {
struct callback_info *next; struct callback_info *next;
@ -63,4 +63,3 @@ private:
} }
#endif // I2C or SPI #endif // I2C or SPI

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include "GPIO.h" #include "GPIO.h"
@ -130,7 +130,7 @@ AP_HAL::DigitalSource* GPIO::channel(uint16_t pin)
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
/* /*
Attach an interrupt handler to a GPIO pin number. The pin number Attach an interrupt handler to a GPIO pin number. The pin number
must be one specified with a GPIO() marker in hwdef.dat must be one specified with a GPIO() marker in hwdef.dat
*/ */
@ -188,7 +188,7 @@ bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t m
return false; return false;
} }
break; break;
} }
osalSysLock(); osalSysLock();
palevent_t *pep = pal_lld_get_line_event(line); palevent_t *pep = pal_lld_get_line_event(line);
@ -260,4 +260,3 @@ void pal_interrupt_cb_functor(void *arg)
} }
(g->fn)(g->pin_num, palReadLine(g->pal_line), now); (g->fn)(g->pin_num, palReadLine(g->pal_line), now);
} }

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -55,7 +55,7 @@ public:
/* attach interrupt via ioline_t */ /* attach interrupt via ioline_t */
bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode); bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode);
private: private:
bool _usb_connected; bool _usb_connected;
bool _ext_started; bool _ext_started;

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -178,13 +178,13 @@ static void main_loop()
ChibiOS::Shared_DMA::init(); ChibiOS::Shared_DMA::init();
peripheral_power_enable(); peripheral_power_enable();
hal.uartA->begin(115200); hal.uartA->begin(115200);
#ifdef HAL_SPI_CHECK_CLOCK_FREQ #ifdef HAL_SPI_CHECK_CLOCK_FREQ
// optional test of SPI clock frequencies // optional test of SPI clock frequencies
ChibiOS::SPIDevice::test_clock_freq(); ChibiOS::SPIDevice::test_clock_freq();
#endif #endif
hal.uartB->begin(38400); hal.uartB->begin(38400);
hal.uartC->begin(57600); hal.uartC->begin(57600);
@ -242,7 +242,7 @@ static void main_loop()
thread_running = true; thread_running = true;
chRegSetThreadName(SKETCHNAME); chRegSetThreadName(SKETCHNAME);
/* /*
switch to high priority for main loop switch to high priority for main loop
*/ */
@ -282,7 +282,7 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
#ifdef HAL_USB_PRODUCT_ID #ifdef HAL_USB_PRODUCT_ID
setup_usb_strings(); setup_usb_strings();
#endif #endif
#ifdef HAL_STDOUT_SERIAL #ifdef HAL_STDOUT_SERIAL
//STDOUT Initialistion //STDOUT Initialistion
SerialConfig stdoutcfg = SerialConfig stdoutcfg =

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once

View File

@ -65,9 +65,9 @@ I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)];
void I2CBus::dma_init(void) void I2CBus::dma_init(void)
{ {
chMtxObjectInit(&dma_lock); chMtxObjectInit(&dma_lock);
dma_handle = new Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx, dma_handle = new Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx,
FUNCTOR_BIND_MEMBER(&I2CBus::dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&I2CBus::dma_allocate, void, Shared_DMA *),
FUNCTOR_BIND_MEMBER(&I2CBus::dma_deallocate, void, Shared_DMA *)); FUNCTOR_BIND_MEMBER(&I2CBus::dma_deallocate, void, Shared_DMA *));
} }
// Clear Bus to avoid bus lockup // Clear Bus to avoid bus lockup
@ -174,7 +174,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u
I2CDevice::~I2CDevice() I2CDevice::~I2CDevice()
{ {
#if 0 #if 0
printf("I2C device bus %u address 0x%02x closed\n", printf("I2C device bus %u address 0x%02x closed\n",
(unsigned)bus.busnum, (unsigned)_address); (unsigned)bus.busnum, (unsigned)_address);
#endif #endif
free(pname); free(pname);
@ -201,7 +201,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
hal.console->printf("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address); hal.console->printf("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address);
return false; return false;
} }
#if defined(STM32F7) || defined(STM32H7) #if defined(STM32F7) || defined(STM32H7)
if (_use_smbus) { if (_use_smbus) {
bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN; bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN;
@ -248,7 +248,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
i2cAcquireBus(I2CD[bus.busnum].i2c); i2cAcquireBus(I2CD[bus.busnum].i2c);
bus.bouncebuffer_setup(send, send_len, recv, recv_len); bus.bouncebuffer_setup(send, send_len, recv, recv_len);
for(uint8_t i=0 ; i <= _retries; i++) { for(uint8_t i=0 ; i <= _retries; i++) {
int ret; int ret;
// calculate a timeout as twice the expected transfer time, and set as min of 4ms // calculate a timeout as twice the expected transfer time, and set as min of 4ms
@ -262,7 +262,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg); i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg);
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state"); osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
osalSysLock(); osalSysLock();
hal.util->persistent_data.i2c_count++; hal.util->persistent_data.i2c_count++;
osalSysUnlock(); osalSysUnlock();
@ -278,7 +278,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state"); osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state");
bus.dma_handle->unlock(); bus.dma_handle->unlock();
if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) { if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) {
AP::internalerror().error(AP_InternalError::error_t::i2c_isr); AP::internalerror().error(AP_InternalError::error_t::i2c_isr);
break; break;
@ -311,7 +311,7 @@ bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
return false; return false;
} }
/* /*
register a periodic callback register a periodic callback
*/ */
@ -319,7 +319,7 @@ AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t pe
{ {
return bus.register_periodic_callback(period_usec, cb, this); return bus.register_periodic_callback(period_usec, cb, this);
} }
/* /*
adjust a periodic callback adjust a periodic callback

View File

@ -13,7 +13,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Modified for use in AP_HAL_ChibiOS by Andrew Tridgell and Siddharth Bharat Purohit * Modified for use in AP_HAL_ChibiOS by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
@ -45,7 +45,7 @@ public:
// have two DMA channels that we are handling with the shared_dma // have two DMA channels that we are handling with the shared_dma
// code // code
mutex_t dma_lock; mutex_t dma_lock;
void dma_allocate(Shared_DMA *); void dma_allocate(Shared_DMA *);
void dma_deallocate(Shared_DMA *); void dma_deallocate(Shared_DMA *);
void dma_init(void); void dma_init(void);
@ -53,7 +53,7 @@ public:
static void clear_bus(uint8_t busidx); static void clear_bus(uint8_t busidx);
static uint8_t read_sda(uint8_t busidx); static uint8_t read_sda(uint8_t busidx);
}; };
class I2CDevice : public AP_HAL::I2CDevice { class I2CDevice : public AP_HAL::I2CDevice {
public: public:
static I2CDevice *from(AP_HAL::I2CDevice *dev) static I2CDevice *from(AP_HAL::I2CDevice *dev)
@ -95,7 +95,7 @@ public:
void set_split_transfers(bool set) override { void set_split_transfers(bool set) override {
_split_transfers = set; _split_transfers = set;
} }
private: private:
I2CBus &bus; I2CBus &bus;
bool _transfer(const uint8_t *send, uint32_t send_len, bool _transfer(const uint8_t *send, uint32_t send_len,
@ -115,10 +115,10 @@ public:
friend class I2CDevice; friend class I2CDevice;
static I2CBus businfo[]; static I2CBus businfo[];
// constructor // constructor
I2CDeviceManager(); I2CDeviceManager();
static I2CDeviceManager *from(AP_HAL::I2CDeviceManager *i2c_mgr) static I2CDeviceManager *from(AP_HAL::I2CDeviceManager *i2c_mgr)
{ {
return static_cast<I2CDeviceManager*>(i2c_mgr); return static_cast<I2CDeviceManager*>(i2c_mgr);
@ -147,4 +147,3 @@ public:
} }
#endif // HAL_USE_I2C #endif // HAL_USE_I2C

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include "RCInput.h" #include "RCInput.h"
@ -73,7 +73,7 @@ bool RCInput::new_input()
radio->init(); radio->init();
} }
} }
#endif #endif
return valid; return valid;
} }
@ -107,7 +107,7 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len)
if (!_init) { if (!_init) {
return false; return false;
} }
if (len > RC_INPUT_MAX_CHANNELS) { if (len > RC_INPUT_MAX_CHANNELS) {
len = RC_INPUT_MAX_CHANNELS; len = RC_INPUT_MAX_CHANNELS;
} }

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once

View File

@ -98,7 +98,7 @@ void RCOutput::set_freq_group(pwm_group &group)
// speed setup in DMA handler // speed setup in DMA handler
return; return;
} }
uint16_t freq_set = group.rc_frequency; uint16_t freq_set = group.rc_frequency;
uint32_t old_clock = group.pwm_cfg.frequency; uint32_t old_clock = group.pwm_cfg.frequency;
uint32_t old_period = group.pwm_cfg.period; uint32_t old_period = group.pwm_cfg.period;
@ -132,7 +132,7 @@ void RCOutput::set_freq_group(pwm_group &group)
} else { } else {
group.pwm_cfg.period = group.pwm_cfg.frequency/freq_set; group.pwm_cfg.period = group.pwm_cfg.frequency/freq_set;
} }
bool force_reconfig = false; bool force_reconfig = false;
for (uint8_t j=0; j<4; j++) { for (uint8_t j=0; j<4; j++) {
if (group.pwm_cfg.channels[j].mode == PWM_OUTPUT_ACTIVE_LOW) { if (group.pwm_cfg.channels[j].mode == PWM_OUTPUT_ACTIVE_LOW) {
@ -323,7 +323,7 @@ void RCOutput::write(uint8_t chan, uint16_t period_us)
if (chan < chan_offset) { if (chan < chan_offset) {
return; return;
} }
if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) { if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) {
// implement safety pwm value // implement safety pwm value
period_us = safe_pwm[chan]; period_us = safe_pwm[chan];
@ -376,7 +376,7 @@ void RCOutput::push_local(void)
// safety is on, overwride pwm // safety is on, overwride pwm
period_us = safe_pwm[chan+chan_offset]; period_us = safe_pwm[chan+chan_offset];
} }
if (group.current_mode == MODE_PWM_BRUSHED) { if (group.current_mode == MODE_PWM_BRUSHED) {
if (period_us <= _esc_pwm_min) { if (period_us <= _esc_pwm_min) {
period_us = 0; period_us = 0;
@ -393,12 +393,12 @@ void RCOutput::push_local(void)
pwmEnableChannel(group.pwm_drv, j, width); pwmEnableChannel(group.pwm_drv, j, width);
// scale the period down so we don't delay for longer than we need to // scale the period down so we don't delay for longer than we need to
period_us /= 8; period_us /= 8;
} }
else if (group.current_mode < MODE_PWM_DSHOT150) { else if (group.current_mode < MODE_PWM_DSHOT150) {
uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us; uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;
pwmEnableChannel(group.pwm_drv, j, width); pwmEnableChannel(group.pwm_drv, j, width);
} }
#ifndef DISABLE_DSHOT #ifndef DISABLE_DSHOT
else if (is_dshot_protocol(group.current_mode) || group.current_mode == MODE_NEOPIXEL) { else if (is_dshot_protocol(group.current_mode) || group.current_mode == MODE_NEOPIXEL) {
// set period_us to time for pulse output, to enable very fast rates // set period_us to time for pulse output, to enable very fast rates
period_us = dshot_pulse_time_us; period_us = dshot_pulse_time_us;
@ -524,7 +524,7 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_
// hold the lock during setup, to ensure there isn't a DMA operation ongoing // hold the lock during setup, to ensure there isn't a DMA operation ongoing
group.dma_handle->lock(); group.dma_handle->lock();
// configure timer driver for DMAR at requested rate // configure timer driver for DMAR at requested rate
if (group.pwm_started) { if (group.pwm_started) {
pwmStop(group.pwm_drv); pwmStop(group.pwm_drv);
@ -561,10 +561,10 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_
} }
} }
} }
pwmStart(group.pwm_drv, &group.pwm_cfg); pwmStart(group.pwm_drv, &group.pwm_cfg);
group.pwm_started = true; group.pwm_started = true;
for (uint8_t j=0; j<4; j++) { for (uint8_t j=0; j<4; j++) {
if (group.chan[j] != CHAN_DISABLED) { if (group.chan[j] != CHAN_DISABLED) {
pwmEnableChannel(group.pwm_drv, j, 0); pwmEnableChannel(group.pwm_drv, j, 0);
@ -579,7 +579,7 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_
/* /*
setup output mode for a group, using group.current_mode. Used to restore output setup output mode for a group, using group.current_mode. Used to restore output
after serial operations after serial operations
*/ */
void RCOutput::set_group_mode(pwm_group &group) void RCOutput::set_group_mode(pwm_group &group)
@ -588,7 +588,7 @@ void RCOutput::set_group_mode(pwm_group &group)
pwmStop(group.pwm_drv); pwmStop(group.pwm_drv);
group.pwm_started = false; group.pwm_started = false;
} }
switch (group.current_mode) { switch (group.current_mode) {
case MODE_PWM_BRUSHED: case MODE_PWM_BRUSHED:
// force zero output initially // force zero output initially
@ -637,7 +637,7 @@ void RCOutput::set_group_mode(pwm_group &group)
dshot_pulse_time_us = 1000000UL * dshot_bit_length / rate; dshot_pulse_time_us = 1000000UL * dshot_bit_length / rate;
break; break;
} }
case MODE_PWM_ONESHOT: case MODE_PWM_ONESHOT:
case MODE_PWM_ONESHOT125: case MODE_PWM_ONESHOT125:
// for oneshot we set a period of 0, which results in no pulses till we trigger // for oneshot we set a period of 0, which results in no pulses till we trigger
@ -655,7 +655,7 @@ void RCOutput::set_group_mode(pwm_group &group)
} }
set_freq_group(group); set_freq_group(group);
if (group.current_mode != MODE_PWM_NONE && if (group.current_mode != MODE_PWM_NONE &&
!group.pwm_started) { !group.pwm_started) {
pwmStart(group.pwm_drv, &group.pwm_cfg); pwmStart(group.pwm_drv, &group.pwm_cfg);
@ -788,7 +788,7 @@ void RCOutput::trigger_groups(void)
} }
} }
} }
/* /*
calculate time that we are allowed to trigger next pulse calculate time that we are allowed to trigger next pulse
to guarantee at least a 50us gap between pulses to guarantee at least a 50us gap between pulses
@ -805,7 +805,7 @@ void RCOutput::trigger_groups(void)
void RCOutput::timer_tick(void) void RCOutput::timer_tick(void)
{ {
safety_update(); safety_update();
uint64_t now = AP_HAL::micros64(); uint64_t now = AP_HAL::micros64();
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
pwm_group &group = pwm_group_list[i]; pwm_group &group = pwm_group_list[i];
@ -933,7 +933,7 @@ void RCOutput::dshot_send(pwm_group &group, bool blocking)
// doing serial output, don't send DShot pulses // doing serial output, don't send DShot pulses
return; return;
} }
if (blocking) { if (blocking) {
group.dma_handle->lock(); group.dma_handle->lock();
} else { } else {
@ -941,11 +941,11 @@ void RCOutput::dshot_send(pwm_group &group, bool blocking)
return; return;
} }
} }
bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED; bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
memset((uint8_t *)group.dma_buffer, 0, dshot_buffer_length); memset((uint8_t *)group.dma_buffer, 0, dshot_buffer_length);
for (uint8_t i=0; i<4; i++) { for (uint8_t i=0; i<4; i++) {
uint8_t chan = group.chan[i]; uint8_t chan = group.chan[i];
if (chan != CHAN_DISABLED) { if (chan != CHAN_DISABLED) {
@ -955,7 +955,7 @@ void RCOutput::dshot_send(pwm_group &group, bool blocking)
// safety is on, overwride pwm // safety is on, overwride pwm
pwm = safe_pwm[chan+chan_offset]; pwm = safe_pwm[chan+chan_offset];
} }
const uint16_t chan_mask = (1U<<chan); const uint16_t chan_mask = (1U<<chan);
if (pwm == 0) { if (pwm == 0) {
// no output // no output
@ -1092,7 +1092,7 @@ void RCOutput::dma_irq_callback(void *p, uint32_t flags)
baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8 baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
databits. This is used for passthrough ESC configuration and databits. This is used for passthrough ESC configuration and
firmware flashing firmware flashing
While serial output is active normal output to the channel group is While serial output is active normal output to the channel group is
suspended. suspended.
*/ */
@ -1102,7 +1102,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t cha
chan -= chan_offset; chan -= chan_offset;
chanmask >>= chan_offset; chanmask >>= chan_offset;
pwm_group *new_serial_group = nullptr; pwm_group *new_serial_group = nullptr;
// find the channel group // find the channel group
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
pwm_group &group = pwm_group_list[i]; pwm_group &group = pwm_group_list[i];
@ -1149,10 +1149,10 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t cha
serial_thread = chThdGetSelfX(); serial_thread = chThdGetSelfX();
serial_priority = chThdGetSelfX()->realprio; serial_priority = chThdGetSelfX()->realprio;
chThdSetPriority(HIGHPRIO); chThdSetPriority(HIGHPRIO);
// remember the bit period for serial_read_byte() // remember the bit period for serial_read_byte()
serial_group->serial.bit_time_us = 1000000UL / baudrate; serial_group->serial.bit_time_us = 1000000UL / baudrate;
// remember the thread that set things up. This is also used to // remember the thread that set things up. This is also used to
// mark the group as doing serial output, so normal output is // mark the group as doing serial output, so normal output is
// suspended // suspended
@ -1160,7 +1160,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t cha
return true; return true;
} }
/* /*
fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit
@ -1190,11 +1190,11 @@ void RCOutput::fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b,
bool RCOutput::serial_write_byte(uint8_t b) bool RCOutput::serial_write_byte(uint8_t b)
{ {
chEvtGetAndClearEvents(serial_event_mask); chEvtGetAndClearEvents(serial_event_mask);
fill_DMA_buffer_byte(serial_group->dma_buffer+serial_group->serial.chan, 4, b, serial_group->bit_width_mul*10); fill_DMA_buffer_byte(serial_group->dma_buffer+serial_group->serial.chan, 4, b, serial_group->bit_width_mul*10);
serial_group->in_serial_dma = true; serial_group->in_serial_dma = true;
// start sending the pulses out // start sending the pulses out
send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t)); send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t));
@ -1202,7 +1202,7 @@ bool RCOutput::serial_write_byte(uint8_t b)
eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(2)); eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(2));
serial_group->in_serial_dma = false; serial_group->in_serial_dma = false;
return (mask & serial_event_mask) != 0; return (mask & serial_event_mask) != 0;
} }
@ -1227,7 +1227,7 @@ bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
// add a small delay for last word of output to have completely // add a small delay for last word of output to have completely
// finished // finished
hal.scheduler->delay_microseconds(25); hal.scheduler->delay_microseconds(25);
serial_group->dma_handle->unlock(); serial_group->dma_handle->unlock();
return true; return true;
#else #else
@ -1248,7 +1248,7 @@ void RCOutput::serial_bit_irq(void)
#if RCOU_SERIAL_TIMING_DEBUG #if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO55, bit); palWriteLine(HAL_GPIO_LINE_GPIO55, bit);
#endif #endif
if (irq.nbits == 0 || bit == irq.last_bit) { if (irq.nbits == 0 || bit == irq.last_bit) {
// start of byte, should be low // start of byte, should be low
if (bit != 0) { if (bit != 0) {
@ -1286,7 +1286,7 @@ void RCOutput::serial_bit_irq(void)
} }
} }
irq.last_bit = bit; irq.last_bit = bit;
if (send_signal) { if (send_signal) {
chSysLockFromISR(); chSysLockFromISR();
chVTResetI(&irq.serial_timeout); chVTResetI(&irq.serial_timeout);
@ -1325,7 +1325,7 @@ bool RCOutput::serial_read_byte(uint8_t &b)
} }
byteval = irq.bitmask | 0x200; byteval = irq.bitmask | 0x200;
} }
if ((byteval & 0x201) != 0x200) { if ((byteval & 0x201) != 0x200) {
// wrong start/stop bits // wrong start/stop bits
return false; return false;
@ -1354,7 +1354,7 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
hal.gpio->pinMode(54, 1); hal.gpio->pinMode(54, 1);
hal.gpio->pinMode(55, 1); hal.gpio->pinMode(55, 1);
#endif #endif
// assume GPIO mappings for PWM outputs start at 50 // assume GPIO mappings for PWM outputs start at 50
palSetLineMode(line, gpio_mode); palSetLineMode(line, gpio_mode);
@ -1372,14 +1372,14 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
#if RCOU_SERIAL_TIMING_DEBUG #if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO54, 1); palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
#endif #endif
if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, AP_HAL::GPIO::INTERRUPT_BOTH)) { if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, AP_HAL::GPIO::INTERRUPT_BOTH)) {
#if RCOU_SERIAL_TIMING_DEBUG #if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO54, 0); palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
#endif #endif
return false; return false;
} }
for (i=0; i<len; i++) { for (i=0; i<len; i++) {
if (!serial_read_byte(buf[i])) { if (!serial_read_byte(buf[i])) {
break; break;
@ -1388,7 +1388,7 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0); ((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0);
irq.waiter = nullptr; irq.waiter = nullptr;
palSetLineMode(line, restore_mode); palSetLineMode(line, restore_mode);
#if RCOU_SERIAL_TIMING_DEBUG #if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO54, 0); palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
@ -1509,7 +1509,7 @@ void RCOutput::safety_update(void)
// remember mask of channels to allow with safety on // remember mask of channels to allow with safety on
safety_mask = boardconfig->get_safety_mask(); safety_mask = boardconfig->get_safety_mask();
} }
#ifdef HAL_GPIO_PIN_SAFETY_IN #ifdef HAL_GPIO_PIN_SAFETY_IN
// handle safety button // handle safety button
bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN); bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -53,7 +53,7 @@ public:
float scale_esc_to_unity(uint16_t pwm) override { float scale_esc_to_unity(uint16_t pwm) override {
return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0; return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
} }
void cork(void) override; void cork(void) override;
void push(void) override; void push(void) override;
@ -72,7 +72,7 @@ public:
in the safe state in the safe state
*/ */
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override; void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
bool enable_px4io_sbus_out(uint16_t rate_hz) override; bool enable_px4io_sbus_out(uint16_t rate_hz) override;
/* /*
@ -117,7 +117,7 @@ public:
return the number of bytes read return the number of bytes read
*/ */
uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override; uint16_t serial_read_bytes(uint8_t *buf, uint16_t len) override;
/* /*
stop serial output. This restores the previous output mode for stop serial output. This restores the previous output mode for
the channel and any other channels that were stopped by the channel and any other channels that were stopped by
@ -171,7 +171,7 @@ public:
trigger send of neopixel data trigger send of neopixel data
*/ */
void neopixel_send(void) override; void neopixel_send(void) override;
private: private:
struct pwm_group { struct pwm_group {
// only advanced timers can do high clocks needed for more than 400Hz // only advanced timers can do high clocks needed for more than 400Hz
@ -201,17 +201,17 @@ private:
uint64_t last_dmar_send_us; uint64_t last_dmar_send_us;
virtual_timer_t dma_timeout; virtual_timer_t dma_timeout;
uint8_t neopixel_nleds; uint8_t neopixel_nleds;
// serial output // serial output
struct { struct {
// expected time per bit // expected time per bit
uint32_t bit_time_us; uint32_t bit_time_us;
// channel to output to within group (0 to 3) // channel to output to within group (0 to 3)
uint8_t chan; uint8_t chan;
// thread waiting for byte to be written // thread waiting for byte to be written
thread_t *waiter; thread_t *waiter;
} serial; } serial;
}; };
@ -231,7 +231,7 @@ private:
// bitmask of bits so far (includes start and stop bits) // bitmask of bits so far (includes start and stop bits)
uint16_t bitmask; uint16_t bitmask;
// value of completed byte (includes start and stop bits) // value of completed byte (includes start and stop bits)
uint16_t byteval; uint16_t byteval;
// expected time per bit in system ticks // expected time per bit in system ticks
@ -239,7 +239,7 @@ private:
// the bit value of the last bit received // the bit value of the last bit received
uint8_t last_bit; uint8_t last_bit;
// thread waiting for byte to be read // thread waiting for byte to be read
thread_t *waiter; thread_t *waiter;
@ -248,12 +248,12 @@ private:
bool timed_out; bool timed_out;
} irq; } irq;
// the group being used for serial output // the group being used for serial output
struct pwm_group *serial_group; struct pwm_group *serial_group;
thread_t *serial_thread; thread_t *serial_thread;
tprio_t serial_priority; tprio_t serial_priority;
static pwm_group pwm_group_list[]; static pwm_group pwm_group_list[];
uint16_t _esc_pwm_min; uint16_t _esc_pwm_min;
uint16_t _esc_pwm_max; uint16_t _esc_pwm_max;
@ -266,12 +266,12 @@ private:
// number of active fmu channels // number of active fmu channels
uint8_t active_fmu_channels; uint8_t active_fmu_channels;
static const uint8_t max_channels = 16; static const uint8_t max_channels = 16;
// last sent values are for all channels // last sent values are for all channels
uint16_t last_sent[max_channels]; uint16_t last_sent[max_channels];
// these values are for the local channels. Non-local channels are handled by IOMCU // these values are for the local channels. Non-local channels are handled by IOMCU
uint32_t en_mask; uint32_t en_mask;
uint16_t period[max_channels]; uint16_t period[max_channels];
@ -321,7 +321,7 @@ private:
// update safety switch and LED // update safety switch and LED
void safety_update(void); void safety_update(void);
/* /*
DShot handling DShot handling
*/ */
@ -341,7 +341,7 @@ private:
bool neopixel_pending; bool neopixel_pending;
void dma_allocate(Shared_DMA *ctx); void dma_allocate(Shared_DMA *ctx);
void dma_deallocate(Shared_DMA *ctx); void dma_deallocate(Shared_DMA *ctx);
uint16_t create_dshot_packet(const uint16_t value, bool telem_request); uint16_t create_dshot_packet(const uint16_t value, bool telem_request);
void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul);
void dshot_send(pwm_group &group, bool blocking); void dshot_send(pwm_group &group, bool blocking);

View File

@ -62,7 +62,7 @@ static const uint32_t bus_clocks[6] = {
SPI1_CLOCK, SPI2_CLOCK, SPI3_CLOCK, SPI4_CLOCK, SPI5_CLOCK, SPI6_CLOCK SPI1_CLOCK, SPI2_CLOCK, SPI3_CLOCK, SPI4_CLOCK, SPI5_CLOCK, SPI6_CLOCK
}; };
static const struct SPIDriverInfo { static const struct SPIDriverInfo {
SPIDriver *driver; SPIDriver *driver;
uint8_t busid; // used for device IDs in parameters uint8_t busid; // used for device IDs in parameters
uint8_t dma_channel_rx; uint8_t dma_channel_rx;
@ -79,13 +79,13 @@ SPIBus::SPIBus(uint8_t _bus) :
bus(_bus) bus(_bus)
{ {
chMtxObjectInit(&dma_lock); chMtxObjectInit(&dma_lock);
// allow for sharing of DMA channels with other peripherals // allow for sharing of DMA channels with other peripherals
dma_handle = new Shared_DMA(spi_devices[bus].dma_channel_rx, dma_handle = new Shared_DMA(spi_devices[bus].dma_channel_rx,
spi_devices[bus].dma_channel_tx, spi_devices[bus].dma_channel_tx,
FUNCTOR_BIND_MEMBER(&SPIBus::dma_allocate, void, Shared_DMA *), FUNCTOR_BIND_MEMBER(&SPIBus::dma_allocate, void, Shared_DMA *),
FUNCTOR_BIND_MEMBER(&SPIBus::dma_deallocate, void, Shared_DMA *)); FUNCTOR_BIND_MEMBER(&SPIBus::dma_deallocate, void, Shared_DMA *));
} }
/* /*
@ -101,13 +101,13 @@ void SPIBus::dma_allocate(Shared_DMA *ctx)
*/ */
void SPIBus::dma_deallocate(Shared_DMA *ctx) void SPIBus::dma_deallocate(Shared_DMA *ctx)
{ {
chMtxLock(&dma_lock); chMtxLock(&dma_lock);
// another non-SPI peripheral wants one of our DMA channels // another non-SPI peripheral wants one of our DMA channels
if (spi_started) { if (spi_started) {
spiStop(spi_devices[bus].driver); spiStop(spi_devices[bus].driver);
spi_started = false; spi_started = false;
} }
chMtxUnlock(&dma_lock); chMtxUnlock(&dma_lock);
} }
@ -242,7 +242,7 @@ uint32_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
spi_clock_freq >>= 1; spi_clock_freq >>= 1;
i++; i++;
} }
// assuming the bitrate bits are consecutive in the CR1 register, // assuming the bitrate bits are consecutive in the CR1 register,
// we can just multiply by BR_0 to get the right bits for the desired // we can just multiply by BR_0 to get the right bits for the desired
// scaling // scaling

View File

@ -37,7 +37,7 @@ public:
void dma_deallocate(Shared_DMA *ctx); void dma_deallocate(Shared_DMA *ctx);
bool spi_started; bool spi_started;
uint8_t slowdown; uint8_t slowdown;
// we need an additional lock in the dma_allocate and // we need an additional lock in the dma_allocate and
// dma_deallocate functions to cope with 3-way contention as we // dma_deallocate functions to cope with 3-way contention as we
// have two DMA channels that we are handling with the shared_dma // have two DMA channels that we are handling with the shared_dma
@ -82,12 +82,12 @@ public:
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, bool transfer_fullduplex(const uint8_t *send, uint8_t *recv,
uint32_t len) override; uint32_t len) override;
/* /*
* send N bytes of clock pulses without taking CS. This is used * send N bytes of clock pulses without taking CS. This is used
* when initialising microSD interfaces over SPI * when initialising microSD interfaces over SPI
*/ */
bool clock_pulse(uint32_t len) override; bool clock_pulse(uint32_t len) override;
/* See AP_HAL::Device::get_semaphore() */ /* See AP_HAL::Device::get_semaphore() */
AP_HAL::Semaphore *get_semaphore() override; AP_HAL::Semaphore *get_semaphore() override;

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -225,7 +225,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc)
return; return;
} }
} }
if (_num_io_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) { if (_num_io_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
_io_proc[_num_io_procs] = proc; _io_proc[_num_io_procs] = proc;
_num_io_procs++; _num_io_procs++;
@ -268,7 +268,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
// disable all interrupt sources // disable all interrupt sources
port_disable(); port_disable();
// reboot // reboot
NVIC_SystemReset(); NVIC_SystemReset();
} }

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -104,7 +104,7 @@ public:
A value of zero cancels the previous expected delay A value of zero cancels the previous expected delay
*/ */
void expect_delay_ms(uint32_t ms) override; void expect_delay_ms(uint32_t ms) override;
/* /*
disable interrupts and return a context that can be used to disable interrupts and return a context that can be used to
restore the interrupt state. This can be used to protect restore the interrupt state. This can be used to protect
@ -163,6 +163,6 @@ private:
void _run_timers(); void _run_timers();
void _run_io(void); void _run_io(void);
static void thread_create_trampoline(void *ctx); static void thread_create_trampoline(void *ctx);
}; };
#endif #endif

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -150,4 +150,3 @@ bool Semaphore_Recursive::take_nonblocking(void)
} }
#endif // CH_CFG_USE_MUTEXES #endif // CH_CFG_USE_MUTEXES

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -57,4 +57,3 @@ private:
}; };
#endif // HAL_USE_ICU #endif // HAL_USE_ICU

View File

@ -63,7 +63,7 @@ void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
for (int i=0; i< EICU_CHANNEL_ENUM_END; i++) { for (int i=0; i< EICU_CHANNEL_ENUM_END; i++) {
icucfg.iccfgp[i]=nullptr; icucfg.iccfgp[i]=nullptr;
} }
//configure main channel //configure main channel
icucfg.iccfgp[chan] = &channel_config; icucfg.iccfgp[chan] = &channel_config;
#ifdef HAL_RCIN_IS_INVERTED #ifdef HAL_RCIN_IS_INVERTED
@ -72,7 +72,7 @@ void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
channel_config.alvl = EICU_INPUT_ACTIVE_LOW; channel_config.alvl = EICU_INPUT_ACTIVE_LOW;
#endif #endif
channel_config.capture_cb = nullptr; channel_config.capture_cb = nullptr;
//configure aux channel //configure aux channel
icucfg.iccfgp[aux_chan] = &aux_channel_config; icucfg.iccfgp[aux_chan] = &aux_channel_config;
#ifdef HAL_RCIN_IS_INVERTED #ifdef HAL_RCIN_IS_INVERTED
@ -85,7 +85,7 @@ void SoftSigReaderInt::init(EICUDriver* icu_drv, eicuchannel_t chan)
eicuStart(_icu_drv, &icucfg); eicuStart(_icu_drv, &icucfg);
//sets input filtering to 4 timer clock //sets input filtering to 4 timer clock
stm32_timer_set_input_filter(_icu_drv->tim, chan, 2); stm32_timer_set_input_filter(_icu_drv->tim, chan, 2);
//sets input for aux_chan //sets input for aux_chan
stm32_timer_set_channel_input(_icu_drv->tim, aux_chan, 2); stm32_timer_set_channel_input(_icu_drv->tim, aux_chan, 2);
eicuEnable(_icu_drv); eicuEnable(_icu_drv);
} }
@ -96,10 +96,10 @@ void SoftSigReaderInt::_irq_handler(EICUDriver *eicup, eicuchannel_t aux_channel
pulse_t pulse; pulse_t pulse;
pulse.w0 = eicup->tim->CCR[channel]; pulse.w0 = eicup->tim->CCR[channel];
pulse.w1 = eicup->tim->CCR[aux_channel]; pulse.w1 = eicup->tim->CCR[aux_channel];
_singleton->sigbuf.push(pulse); _singleton->sigbuf.push(pulse);
//check for missed interrupt //check for missed interrupt
uint32_t mask = (STM32_TIM_SR_CC1OF << channel) | (STM32_TIM_SR_CC1OF << aux_channel); uint32_t mask = (STM32_TIM_SR_CC1OF << channel) | (STM32_TIM_SR_CC1OF << aux_channel);
if ((eicup->tim->SR & mask) != 0) { if ((eicup->tim->SR & mask) != 0) {
//we have missed some pulses //we have missed some pulses

View File

@ -47,7 +47,7 @@ private:
static SoftSigReaderInt *_singleton; static SoftSigReaderInt *_singleton;
static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel); static void _irq_handler(EICUDriver *eicup, eicuchannel_t channel);
static eicuchannel_t get_pair_channel(eicuchannel_t channel); static eicuchannel_t get_pair_channel(eicuchannel_t channel);
typedef struct PACKED { typedef struct PACKED {
uint16_t w0; uint16_t w0;
@ -62,4 +62,3 @@ private:
}; };
#endif // HAL_USE_EICU #endif // HAL_USE_EICU

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -53,7 +53,7 @@ void Storage::_storage_open(void)
return; return;
} }
#endif #endif
_dirty_mask.clearall(); _dirty_mask.clearall();
#if HAL_WITH_RAMTRON #if HAL_WITH_RAMTRON
@ -75,7 +75,7 @@ void Storage::_storage_open(void)
#elif defined(USE_POSIX) #elif defined(USE_POSIX)
// allow for fallback to microSD based storage // allow for fallback to microSD based storage
sdcard_retry(); sdcard_retry();
log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT); log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
if (log_fd == -1) { if (log_fd == -1) {
hal.console->printf("open failed of " HAL_STORAGE_FILE "\n"); hal.console->printf("open failed of " HAL_STORAGE_FILE "\n");
@ -94,7 +94,7 @@ void Storage::_storage_open(void)
hal.console->printf("setup failed for " HAL_STORAGE_FILE "\n"); hal.console->printf("setup failed for " HAL_STORAGE_FILE "\n");
AP::FS().close(log_fd); AP::FS().close(log_fd);
log_fd = -1; log_fd = -1;
return; return;
} }
using_filesystem = true; using_filesystem = true;
#endif #endif
@ -188,7 +188,7 @@ void Storage::_timer_tick(void)
_dirty_mask.clear(i); _dirty_mask.clear(i);
} }
return; return;
} }
#endif #endif
#ifdef USE_POSIX #ifdef USE_POSIX
@ -205,9 +205,9 @@ void Storage::_timer_tick(void)
} }
_dirty_mask.clear(i); _dirty_mask.clear(i);
return; return;
} }
#endif #endif
#ifdef STORAGE_FLASH_PAGE #ifdef STORAGE_FLASH_PAGE
// save to storage backend // save to storage backend
_flash_write(i); _flash_write(i);
@ -223,7 +223,7 @@ void Storage::_flash_load(void)
_flash_page = STORAGE_FLASH_PAGE; _flash_page = STORAGE_FLASH_PAGE;
hal.console->printf("Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1); hal.console->printf("Storage: Using flash pages %u and %u\n", _flash_page, _flash_page+1);
if (!_flash.init()) { if (!_flash.init()) {
AP_HAL::panic("unable to init flash storage"); AP_HAL::panic("unable to init flash storage");
} }
@ -233,7 +233,7 @@ void Storage::_flash_load(void)
} }
/* /*
write one storage line. This also updates _dirty_mask. write one storage line. This also updates _dirty_mask.
*/ */
void Storage::_flash_write(uint16_t line) void Storage::_flash_write(uint16_t line)
{ {

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -69,7 +69,7 @@ private:
FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_sector, bool, uint8_t), FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_sector, bool, uint8_t),
FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_ok, bool)}; FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_ok, bool)};
#endif #endif
void _flash_load(void); void _flash_load(void);
void _flash_write(uint16_t line); void _flash_write(uint16_t line);

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -139,7 +139,7 @@ static int hal_console_vprintf(const char *fmt, va_list arg)
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{ {
thread_init(); thread_init();
if (sdef.serial == nullptr) { if (sdef.serial == nullptr) {
return; return;
} }
@ -150,7 +150,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
// give more buffer space for log download on USB // give more buffer space for log download on USB
min_tx_buffer *= 4; min_tx_buffer *= 4;
} }
// on PX4 we have enough memory to have a larger transmit and // on PX4 we have enough memory to have a larger transmit and
// receive buffer for all ports. This means we don't get delays // receive buffer for all ports. This means we don't get delays
// while waiting to write GPS config packets // while waiting to write GPS config packets
@ -184,7 +184,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
} }
_baudrate = b; _baudrate = b;
} }
if (clear_buffers) { if (clear_buffers) {
_readbuf.clear(); _readbuf.clear();
} }
@ -382,9 +382,9 @@ void UARTDriver::tx_complete(void* self, uint32_t flags)
UARTDriver* uart_drv = (UARTDriver*)self; UARTDriver* uart_drv = (UARTDriver*)self;
chSysLockFromISR(); chSysLockFromISR();
if (!uart_drv->tx_bounce_buf_ready) { if (!uart_drv->tx_bounce_buf_ready) {
// reset timeout // reset timeout
chVTResetI(&uart_drv->tx_timeout); chVTResetI(&uart_drv->tx_timeout);
uart_drv->_last_write_completed_us = AP_HAL::micros(); uart_drv->_last_write_completed_us = AP_HAL::micros();
uart_drv->tx_bounce_buf_ready = true; uart_drv->tx_bounce_buf_ready = true;
if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) { if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) {
@ -444,14 +444,14 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
uart_drv->receive_timestamp_update(); uart_drv->receive_timestamp_update();
} }
//restart the DMA transfers //restart the DMA transfers
dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf); dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf);
dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE); dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE);
dmaStreamEnable(uart_drv->rxdma); dmaStreamEnable(uart_drv->rxdma);
if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) { if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) {
chSysLockFromISR(); chSysLockFromISR();
chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA); chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA);
chSysUnlockFromISR(); chSysUnlockFromISR();
} }
if (uart_drv->_rts_is_active) { if (uart_drv->_rts_is_active) {
@ -549,7 +549,7 @@ int16_t UARTDriver::read()
if (!_rts_is_active) { if (!_rts_is_active) {
update_rts_line(); update_rts_line();
} }
return byte; return byte;
} }
@ -577,7 +577,7 @@ size_t UARTDriver::write(uint8_t c)
if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) { if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) {
return 0; return 0;
} }
if (!_initialised) { if (!_initialised) {
_write_mutex.give(); _write_mutex.give();
return 0; return 0;
@ -651,7 +651,7 @@ bool UARTDriver::lock_port(uint32_t write_key, uint32_t read_key)
return true; return true;
} }
/* /*
write to a locked port. If port is locked and key is not correct then 0 is returned write to a locked port. If port is locked and key is not correct then 0 is returned
and write is discarded. All writes are non-blocking and write is discarded. All writes are non-blocking
*/ */
@ -811,7 +811,7 @@ void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
nwritten += ret; nwritten += ret;
} }
_writebuf.advance(ret); _writebuf.advance(ret);
/* We wrote less than we asked for, stop */ /* We wrote less than we asked for, stop */
if ((unsigned)ret != vec[i].len) { if ((unsigned)ret != vec[i].len) {
break; break;
@ -843,7 +843,7 @@ void UARTDriver::write_pending_bytes(void)
if (n <= 0) { if (n <= 0) {
return; return;
} }
#ifndef HAL_UART_NODMA #ifndef HAL_UART_NODMA
if (sdef.dma_tx) { if (sdef.dma_tx) {
write_pending_bytes_DMA(n); write_pending_bytes_DMA(n);
@ -852,7 +852,7 @@ void UARTDriver::write_pending_bytes(void)
{ {
write_pending_bytes_NODMA(n); write_pending_bytes_NODMA(n);
} }
// handle AUTO flow control mode // handle AUTO flow control mode
if (_flow_control == FLOW_CONTROL_AUTO) { if (_flow_control == FLOW_CONTROL_AUTO) {
if (_first_write_started_us == 0) { if (_first_write_started_us == 0) {
@ -991,7 +991,7 @@ void UARTDriver::_timer_tick(void)
_readbuf.commit((unsigned)ret); _readbuf.commit((unsigned)ret);
receive_timestamp_update(); receive_timestamp_update();
/* stop reading as we read less than we asked for */ /* stop reading as we read less than we asked for */
if ((unsigned)ret < vec[i].len) { if ((unsigned)ret < vec[i].len) {
break; break;
@ -999,7 +999,7 @@ void UARTDriver::_timer_tick(void)
} }
} }
if (_wait.thread_ctx && _readbuf.available() >= _wait.n) { if (_wait.thread_ctx && _readbuf.available() >= _wait.n) {
chEvtSignal(_wait.thread_ctx, EVT_DATA); chEvtSignal(_wait.thread_ctx, EVT_DATA);
} }
if (unbuffered_writes) { if (unbuffered_writes) {
// now send pending bytes. If we are doing "unbuffered" writes // now send pending bytes. If we are doing "unbuffered" writes
@ -1025,7 +1025,7 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
if (sdef.rts_line == 0 || sdef.is_usb) { if (sdef.rts_line == 0 || sdef.is_usb) {
// no hw flow control available // no hw flow control available
return; return;
} }
#if HAL_USE_SERIAL == TRUE #if HAL_USE_SERIAL == TRUE
SerialDriver *sd = (SerialDriver*)(sdef.serial); SerialDriver *sd = (SerialDriver*)(sdef.serial);
_flow_control = flowcontrol; _flow_control = flowcontrol;
@ -1034,7 +1034,7 @@ void UARTDriver::set_flow_control(enum flow_control flowcontrol)
return; return;
} }
switch (_flow_control) { switch (_flow_control) {
case FLOW_CONTROL_DISABLE: case FLOW_CONTROL_DISABLE:
// force RTS active when flow disabled // force RTS active when flow disabled
palSetLineMode(sdef.rts_line, 1); palSetLineMode(sdef.rts_line, 1);
@ -1096,7 +1096,7 @@ void UARTDriver::update_rts_line(void)
} }
} }
/* /*
setup unbuffered writes for lower latency setup unbuffered writes for lower latency
*/ */
bool UARTDriver::set_unbuffered_writes(bool on) bool UARTDriver::set_unbuffered_writes(bool on)
@ -1166,7 +1166,7 @@ void UARTDriver::configure_parity(uint8_t v)
SD_PARITY_ERROR); SD_PARITY_ERROR);
} }
#endif #endif
#ifndef HAL_UART_NODMA #ifndef HAL_UART_NODMA
if(sdef.dma_rx) { if(sdef.dma_rx) {
//Configure serial driver to skip handling RX packets //Configure serial driver to skip handling RX packets
@ -1189,7 +1189,7 @@ void UARTDriver::set_stop_bits(int n)
#if HAL_USE_SERIAL #if HAL_USE_SERIAL
// stop and start to take effect // stop and start to take effect
sdStop((SerialDriver*)sdef.serial); sdStop((SerialDriver*)sdef.serial);
switch (n) { switch (n) {
case 1: case 1:
sercfg.cr2 = _cr2_options | USART_CR2_STOP1_BITS; sercfg.cr2 = _cr2_options | USART_CR2_STOP1_BITS;
@ -1211,7 +1211,7 @@ void UARTDriver::set_stop_bits(int n)
} }
// record timestamp of new incoming data // record timestamp of new incoming data
void UARTDriver::receive_timestamp_update(void) void UARTDriver::receive_timestamp_update(void)
{ {
_receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64(); _receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64();
@ -1224,11 +1224,11 @@ void UARTDriver::receive_timestamp_update(void)
time constraint, not an exact time. It is guaranteed that the time constraint, not an exact time. It is guaranteed that the
packet did not start being received after this time, but it packet did not start being received after this time, but it
could have been in a system buffer before the returned time. could have been in a system buffer before the returned time.
This takes account of the baudrate of the link. For transports This takes account of the baudrate of the link. For transports
that have no baudrate (such as USB) the time estimate may be that have no baudrate (such as USB) the time estimate may be
less accurate. less accurate.
A return value of zero means the HAL does not support this API A return value of zero means the HAL does not support this API
*/ */
uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -56,11 +56,11 @@ public:
// control optional features // control optional features
bool set_options(uint8_t options) override; bool set_options(uint8_t options) override;
uint8_t get_options(void) const override; uint8_t get_options(void) const override;
// write to a locked port. If port is locked and key is not correct then 0 is returned // write to a locked port. If port is locked and key is not correct then 0 is returned
// and write is discarded // and write is discarded
size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override; size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
struct SerialDef { struct SerialDef {
BaseSequentialStream* serial; BaseSequentialStream* serial;
bool is_usb; bool is_usb;
@ -159,7 +159,7 @@ private:
const stm32_dma_stream_t* rxdma; const stm32_dma_stream_t* rxdma;
const stm32_dma_stream_t* txdma; const stm32_dma_stream_t* txdma;
#endif #endif
virtual_timer_t tx_timeout; virtual_timer_t tx_timeout;
bool _in_timer; bool _in_timer;
bool _blocking_writes; bool _blocking_writes;
bool _initialised; bool _initialised;
@ -201,7 +201,7 @@ private:
event_listener_t ev_listener; event_listener_t ev_listener;
bool parity_enabled; bool parity_enabled;
#endif #endif
#ifndef HAL_UART_NODMA #ifndef HAL_UART_NODMA
static void rx_irq_cb(void* sd); static void rx_irq_cb(void* sd);
#endif #endif
@ -223,7 +223,7 @@ private:
void write_pending_bytes(void); void write_pending_bytes(void);
void receive_timestamp_update(void); void receive_timestamp_update(void);
void thread_init(); void thread_init();
static void uart_thread(void *); static void uart_thread(void *);
}; };

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -133,7 +133,7 @@ void Util::set_imu_temp(float current)
// average over temperatures to remove noise // average over temperatures to remove noise
heater.count++; heater.count++;
heater.sum += current; heater.sum += current;
// update once a second // update once a second
uint32_t now = AP_HAL::millis(); uint32_t now = AP_HAL::millis();
if (now - heater.last_update_ms < 1000) { if (now - heater.last_update_ms < 1000) {
@ -158,14 +158,14 @@ void Util::set_imu_temp(float current)
// limit to 65 degrees to prevent damage // limit to 65 degrees to prevent damage
target = constrain_float(target, 0, 65); target = constrain_float(target, 0, 65);
float err = target - current; float err = target - current;
heater.integrator += kI * err; heater.integrator += kI * err;
heater.integrator = constrain_float(heater.integrator, 0, 70); heater.integrator = constrain_float(heater.integrator, 0, 70);
heater.output = constrain_float(kP * err + heater.integrator, 0, 100); heater.output = constrain_float(kP * err + heater.integrator, 0, 100);
//hal.console->printf("integrator %.1f out=%.1f temp=%.2f err=%.2f\n", heater.integrator, heater.output, current, err); //hal.console->printf("integrator %.1f out=%.1f temp=%.2f err=%.2f\n", heater.integrator, heater.output, current, err);
#if HAL_WITH_IO_MCU #if HAL_WITH_IO_MCU
@ -281,16 +281,16 @@ bool Util::get_system_id(char buf[40])
{ {
uint8_t serialid[12]; uint8_t serialid[12];
char board_name[14]; char board_name[14];
memcpy(serialid, (const void *)UDID_START, 12); memcpy(serialid, (const void *)UDID_START, 12);
strncpy(board_name, CHIBIOS_SHORT_BOARD_NAME, 13); strncpy(board_name, CHIBIOS_SHORT_BOARD_NAME, 13);
board_name[13] = 0; board_name[13] = 0;
// this format is chosen to match the format used by HAL_PX4 // this format is chosen to match the format used by HAL_PX4
snprintf(buf, 40, "%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X", snprintf(buf, 40, "%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
board_name, board_name,
(unsigned)serialid[3], (unsigned)serialid[2], (unsigned)serialid[1], (unsigned)serialid[0], (unsigned)serialid[3], (unsigned)serialid[2], (unsigned)serialid[1], (unsigned)serialid[0],
(unsigned)serialid[7], (unsigned)serialid[6], (unsigned)serialid[5], (unsigned)serialid[4], (unsigned)serialid[7], (unsigned)serialid[6], (unsigned)serialid[5], (unsigned)serialid[4],
(unsigned)serialid[11], (unsigned)serialid[10], (unsigned)serialid[9],(unsigned)serialid[8]); (unsigned)serialid[11], (unsigned)serialid[10], (unsigned)serialid[9],(unsigned)serialid[8]);
buf[39] = 0; buf[39] = 0;
return true; return true;

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once

View File

@ -1,18 +1,18 @@
/* /*
* The MIT License (MIT) * The MIT License (MIT)
* *
* Copyright (c) 2014 Pavel Kirienko * Copyright (c) 2014 Pavel Kirienko
* *
* Permission is hereby granted, free of charge, to any person obtaining a copy of * Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in * this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to * the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so, * the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions: * subject to the following conditions:
* *
* The above copyright notice and this permission notice shall be included in all * The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. * copies or substantial portions of the Software.
* *
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
@ -34,7 +34,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Modified for Ardupilot by Siddharth Bharat Purohit * Modified for Ardupilot by Siddharth Bharat Purohit
*/ */
@ -327,4 +327,4 @@ constexpr unsigned long FMR_FINIT = (1U << 0); /* Bit 0: Filter Init
# undef constexpr # undef constexpr
#endif #endif
#endif //!defined(STM32H7XX) #endif //!defined(STM32H7XX)
#endif //HAL_WITH_UAVCAN #endif //HAL_WITH_UAVCAN

View File

@ -87,4 +87,4 @@ CanType* const Can[UAVCAN_STM32_NUM_IFACES] = {
# undef constexpr # undef constexpr
#endif #endif
#endif //defined(STM32H7XX) #endif //defined(STM32H7XX)
#endif //HAL_WITH_UAVCAN #endif //HAL_WITH_UAVCAN

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
*/ */
#include "SPIDevice.h" #include "SPIDevice.h"
@ -97,7 +97,7 @@ bool sdcard_init()
return false; return false;
} }
device->set_slowdown(sd_slowdown); device->set_slowdown(sd_slowdown);
mmcObjectInit(&MMCD1); mmcObjectInit(&MMCD1);
mmcconfig.spip = mmcconfig.spip =
@ -224,4 +224,3 @@ void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
} }
#endif #endif

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
*/ */
#pragma once #pragma once

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include "shared_dma.h" #include "shared_dma.h"

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#pragma once #pragma once
@ -37,13 +37,13 @@ public:
// initialise the stream locks // initialise the stream locks
static void init(void); static void init(void);
// blocking lock call // blocking lock call
void lock(void); void lock(void);
// non-blocking lock call // non-blocking lock call
bool lock_nonblock(void); bool lock_nonblock(void);
// unlock call. The DMA channel will not be immediately // unlock call. The DMA channel will not be immediately
// deallocated. Instead it will be deallocated if another driver // deallocated. Instead it will be deallocated if another driver
// needs it // needs it
@ -54,17 +54,17 @@ public:
// unlock call from a chSysLock zone // unlock call from a chSysLock zone
void unlock_from_lockzone(void); void unlock_from_lockzone(void);
//should be called inside the destructor of Shared DMA participants //should be called inside the destructor of Shared DMA participants
void unregister(void); void unregister(void);
// return true if this DMA channel is being actively contended for // return true if this DMA channel is being actively contended for
// by multiple drivers // by multiple drivers
bool has_contention(void) const { return contention; } bool has_contention(void) const { return contention; }
// lock all shared DMA channels. Used on reboot // lock all shared DMA channels. Used on reboot
static void lock_all(void); static void lock_all(void);
private: private:
dma_allocate_fn_t allocate; dma_allocate_fn_t allocate;
dma_allocate_fn_t deallocate; dma_allocate_fn_t deallocate;
@ -90,7 +90,7 @@ private:
// lock one stream, non-blocking // lock one stream, non-blocking
bool lock_stream_nonblocking(uint8_t stream_id); bool lock_stream_nonblocking(uint8_t stream_id);
static struct dma_lock { static struct dma_lock {
// semaphore to ensure only one peripheral uses a DMA channel at a time // semaphore to ensure only one peripheral uses a DMA channel at a time
#if CH_CFG_USE_SEMAPHORES == TRUE #if CH_CFG_USE_SEMAPHORES == TRUE
@ -104,6 +104,3 @@ private:
Shared_DMA *obj; Shared_DMA *obj;
} locks[SHARED_DMA_MAX_STREAM_ID+1]; } locks[SHARED_DMA_MAX_STREAM_ID+1];
}; };

View File

@ -36,11 +36,11 @@ int __wrap_snprintf(char *str, size_t size, const char *fmt, ...)
{ {
va_list arg; va_list arg;
int done; int done;
va_start (arg, fmt); va_start (arg, fmt);
done = hal.util->vsnprintf(str, size, fmt, arg); done = hal.util->vsnprintf(str, size, fmt, arg);
va_end (arg); va_end (arg);
return done; return done;
} }
@ -91,11 +91,11 @@ int __wrap_printf(const char *fmt, ...)
#ifndef HAL_NO_PRINTF #ifndef HAL_NO_PRINTF
va_list arg; va_list arg;
int done; int done;
va_start (arg, fmt); va_start (arg, fmt);
done = vprintf_console_hook(fmt, arg); done = vprintf_console_hook(fmt, arg);
va_end (arg); va_end (arg);
return done; return done;
#else #else
(void)fmt; (void)fmt;
@ -112,11 +112,11 @@ int __wrap_fprintf(void *f, const char *fmt, ...)
#ifndef HAL_NO_PRINTF #ifndef HAL_NO_PRINTF
va_list arg; va_list arg;
int done; int done;
va_start (arg, fmt); va_start (arg, fmt);
done = vprintf_console_hook(fmt, arg); done = vprintf_console_hook(fmt, arg);
va_end (arg); va_end (arg);
return done; return done;
#else #else
(void)fmt; (void)fmt;
@ -135,4 +135,3 @@ extern "C" {
// alias fiprintf() to fprintf(). This saves flash space // alias fiprintf() to fprintf(). This saves flash space
int __wrap_fiprintf(const char *fmt, ...) __attribute__((alias("__wrap_fprintf"))); int __wrap_fiprintf(const char *fmt, ...) __attribute__((alias("__wrap_fprintf")));
} }

View File

@ -11,7 +11,7 @@
* *
* You should have received a copy of the GNU General Public License along * You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
* *
* Code by Andrew Tridgell and Siddharth Bharat Purohit * Code by Andrew Tridgell and Siddharth Bharat Purohit
*/ */
#include <stdarg.h> #include <stdarg.h>
@ -40,7 +40,7 @@ typedef enum {
void *__dso_handle; void *__dso_handle;
void __cxa_pure_virtual(void); void __cxa_pure_virtual(void);
void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate a traceback
void NMI_Handler(void); void NMI_Handler(void);