Changes to sonar for new IO
This commit is contained in:
parent
4bd0b0fb9c
commit
c16d642d66
|
@ -189,12 +189,11 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SONAR
|
#ifdef SONAR
|
||||||
if (init->sonarGPIOConfig &&
|
if (init->sonarConfig &&
|
||||||
(
|
(
|
||||||
CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->triggerPin) ||
|
timerHardwarePtr->pin == init->sonarConfig->triggerPin ||
|
||||||
CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->echoPin)
|
timerHardwarePtr->pin == init->sonarConfig->echoPin
|
||||||
)
|
)) {
|
||||||
) {
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
#include "gpio.h"
|
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
#define MAX_PWM_MOTORS 12
|
#define MAX_PWM_MOTORS 12
|
||||||
|
@ -42,11 +42,10 @@
|
||||||
#define ONESHOT42_TIMER_MHZ 24
|
#define ONESHOT42_TIMER_MHZ 24
|
||||||
#define ONESHOT125_TIMER_MHZ 8
|
#define ONESHOT125_TIMER_MHZ 8
|
||||||
|
|
||||||
typedef struct sonarGPIOConfig_s {
|
typedef struct sonarIOConfig_s {
|
||||||
GPIO_TypeDef *gpio;
|
ioTag_t triggerPin;
|
||||||
uint16_t triggerPin;
|
ioTag_t echoPin;
|
||||||
uint16_t echoPin;
|
} sonarIOConfig_t;
|
||||||
} sonarGPIOConfig_t;
|
|
||||||
|
|
||||||
typedef struct drv_pwm_config_s {
|
typedef struct drv_pwm_config_s {
|
||||||
bool useParallelPWM;
|
bool useParallelPWM;
|
||||||
|
@ -78,7 +77,7 @@ typedef struct drv_pwm_config_s {
|
||||||
uint16_t motorPwmRate;
|
uint16_t motorPwmRate;
|
||||||
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
|
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
|
||||||
// some higher value (used by 3d mode), or 0, for brushed pwm drivers.
|
// some higher value (used by 3d mode), or 0, for brushed pwm drivers.
|
||||||
sonarGPIOConfig_t *sonarGPIOConfig;
|
sonarIOConfig_t *sonarConfig;
|
||||||
} drv_pwm_config_t;
|
} drv_pwm_config_t;
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
|
|
|
@ -22,7 +22,6 @@
|
||||||
#include "build_config.h"
|
#include "build_config.h"
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "gpio.h"
|
|
||||||
#include "nvic.h"
|
#include "nvic.h"
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "exti.h"
|
#include "exti.h"
|
||||||
|
@ -43,8 +42,9 @@ static uint32_t lastMeasurementAt;
|
||||||
static sonarHardware_t const *sonarHardware;
|
static sonarHardware_t const *sonarHardware;
|
||||||
|
|
||||||
extiCallbackRec_t hcsr04_extiCallbackRec;
|
extiCallbackRec_t hcsr04_extiCallbackRec;
|
||||||
|
|
||||||
static IO_t echoIO;
|
static IO_t echoIO;
|
||||||
//static IO_t triggerIO;
|
static IO_t triggerIO;
|
||||||
|
|
||||||
void hcsr04_extiHandler(extiCallbackRec_t* cb)
|
void hcsr04_extiHandler(extiCallbackRec_t* cb)
|
||||||
{
|
{
|
||||||
|
@ -52,7 +52,7 @@ void hcsr04_extiHandler(extiCallbackRec_t* cb)
|
||||||
uint32_t timing_stop;
|
uint32_t timing_stop;
|
||||||
UNUSED(cb);
|
UNUSED(cb);
|
||||||
|
|
||||||
if (digitalIn(sonarHardware->echo_gpio, sonarHardware->echo_pin) != 0) {
|
if (IORead(echoIO) != 0) {
|
||||||
timing_start = micros();
|
timing_start = micros();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -71,32 +71,27 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sona
|
||||||
sonarRange->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES;
|
sonarRange->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES;
|
||||||
|
|
||||||
#if !defined(UNIT_TEST)
|
#if !defined(UNIT_TEST)
|
||||||
gpio_config_t gpio;
|
|
||||||
|
|
||||||
#ifdef STM32F10X
|
#ifdef STM32F10X
|
||||||
// enable AFIO for EXTI support
|
// enable AFIO for EXTI support
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
#if defined(STM32F3) || defined(STM32F4)
|
||||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
|
||||||
|
|
||||||
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
|
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// trigger pin
|
// trigger pin
|
||||||
gpio.pin = sonarHardware->trigger_pin;
|
triggerIO = IOGetByTag(sonarHardware->triggerIO);
|
||||||
gpio.mode = Mode_Out_PP;
|
IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT);
|
||||||
gpio.speed = Speed_2MHz;
|
IOConfigGPIO(triggerIO, IOCFG_OUT_PP);
|
||||||
gpioInit(sonarHardware->trigger_gpio, &gpio);
|
|
||||||
|
|
||||||
// echo pin
|
// echo pin
|
||||||
gpio.pin = sonarHardware->echo_pin;
|
echoIO = IOGetByTag(sonarHardware->echoIO);
|
||||||
gpio.mode = Mode_IN_FLOATING;
|
IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT);
|
||||||
gpioInit(sonarHardware->echo_gpio, &gpio);
|
IOConfigGPIO(echoIO, IOCFG_IN_FLOATING);
|
||||||
|
|
||||||
echoIO = IOGetByTag(sonarHardware->echoIO);
|
|
||||||
#ifdef USE_EXTI
|
#ifdef USE_EXTI
|
||||||
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
|
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
|
||||||
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
|
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
|
||||||
|
@ -123,10 +118,10 @@ void hcsr04_start_reading(void)
|
||||||
|
|
||||||
lastMeasurementAt = now;
|
lastMeasurementAt = now;
|
||||||
|
|
||||||
digitalHi(sonarHardware->trigger_gpio, sonarHardware->trigger_pin);
|
IOHi(triggerIO);
|
||||||
// The width of trig signal must be greater than 10us
|
// The width of trig signal must be greater than 10us
|
||||||
delayMicroseconds(11);
|
delayMicroseconds(11);
|
||||||
digitalLo(sonarHardware->trigger_gpio, sonarHardware->trigger_pin);
|
IOLo(triggerIO);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -21,10 +21,6 @@
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
|
|
||||||
typedef struct sonarHardware_s {
|
typedef struct sonarHardware_s {
|
||||||
uint16_t trigger_pin;
|
|
||||||
GPIO_TypeDef* trigger_gpio;
|
|
||||||
uint16_t echo_pin;
|
|
||||||
GPIO_TypeDef* echo_gpio;
|
|
||||||
ioTag_t triggerIO;
|
ioTag_t triggerIO;
|
||||||
ioTag_t echoIO;
|
ioTag_t echoIO;
|
||||||
} sonarHardware_t;
|
} sonarHardware_t;
|
||||||
|
|
|
@ -265,12 +265,11 @@ void init(void)
|
||||||
|
|
||||||
if (feature(FEATURE_SONAR)) {
|
if (feature(FEATURE_SONAR)) {
|
||||||
sonarHardware = sonarGetHardwareConfiguration(&masterConfig.batteryConfig);
|
sonarHardware = sonarGetHardwareConfiguration(&masterConfig.batteryConfig);
|
||||||
sonarGPIOConfig_t sonarGPIOConfig = {
|
sonarIOConfig_t sonarConfig = {
|
||||||
.gpio = SONAR_GPIO,
|
.triggerPin = sonarHardware->triggerIO,
|
||||||
.triggerPin = sonarHardware->echo_pin,
|
.echoPin = sonarHardware->echoIO
|
||||||
.echoPin = sonarHardware->trigger_pin,
|
|
||||||
};
|
};
|
||||||
pwm_params.sonarGPIOConfig = &sonarGPIOConfig;
|
pwm_params.sonarConfig = &sonarConfig;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
|
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/gpio.h"
|
#include "drivers/io.h"
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
|
||||||
|
@ -48,77 +48,14 @@ float sonarMaxTiltCos;
|
||||||
|
|
||||||
static int32_t calculatedAltitude;
|
static int32_t calculatedAltitude;
|
||||||
|
|
||||||
|
#ifndef SONAR_CUSTOM_CONFIG
|
||||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
||||||
{
|
{
|
||||||
#if defined(NAZE) || defined(EUSTM32F103RC) || defined(PORT103R)
|
#if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
|
||||||
static const sonarHardware_t const sonarPWM56 = {
|
|
||||||
.trigger_pin = Pin_8, // PWM5 (PB8) - 5v tolerant
|
|
||||||
.trigger_gpio = GPIOB,
|
|
||||||
.echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PB8),
|
|
||||||
.echoIO = IO_TAG(PB9),
|
|
||||||
};
|
|
||||||
static const sonarHardware_t sonarRC78 = {
|
|
||||||
.trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.trigger_gpio = GPIOB,
|
|
||||||
.echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PB0),
|
|
||||||
.echoIO = IO_TAG(PB1),
|
|
||||||
};
|
|
||||||
// If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
|
|
||||||
if (feature(FEATURE_SOFTSERIAL)
|
|
||||||
|| feature(FEATURE_RX_PARALLEL_PWM )
|
|
||||||
|| (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) {
|
|
||||||
return &sonarPWM56;
|
|
||||||
} else {
|
|
||||||
return &sonarRC78;
|
|
||||||
}
|
|
||||||
#elif defined(OLIMEXINO)
|
|
||||||
UNUSED(batteryConfig);
|
UNUSED(batteryConfig);
|
||||||
static const sonarHardware_t const sonarHardware = {
|
static const sonarHardware_t const sonarHardware = {
|
||||||
.trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
.triggerIO = IO_TAG(SONAR_TRIGGER_PIN),
|
||||||
.trigger_gpio = GPIOB,
|
.echoIO = IO_TAG(SONAR_ECHO_PIN),
|
||||||
.echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PB0),
|
|
||||||
.echoIO = IO_TAG(PB1),
|
|
||||||
};
|
|
||||||
return &sonarHardware;
|
|
||||||
#elif defined(CC3D)
|
|
||||||
UNUSED(batteryConfig);
|
|
||||||
static const sonarHardware_t const sonarHardware = {
|
|
||||||
.trigger_pin = Pin_5, // (PB5)
|
|
||||||
.trigger_gpio = GPIOB,
|
|
||||||
.echo_pin = Pin_0, // (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PB5),
|
|
||||||
.echoIO = IO_TAG(PB0),
|
|
||||||
};
|
|
||||||
return &sonarHardware;
|
|
||||||
|
|
||||||
// TODO - move sonar pin selection to CLI
|
|
||||||
#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) || defined(RMDO)
|
|
||||||
UNUSED(batteryConfig);
|
|
||||||
static const sonarHardware_t const sonarHardware = {
|
|
||||||
.trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.trigger_gpio = GPIOB,
|
|
||||||
.echo_pin = Pin_1, // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PB0),
|
|
||||||
.echoIO = IO_TAG(PB1),
|
|
||||||
};
|
|
||||||
return &sonarHardware;
|
|
||||||
#elif defined(SPARKY)
|
|
||||||
UNUSED(batteryConfig);
|
|
||||||
static const sonarHardware_t const sonarHardware = {
|
|
||||||
.trigger_pin = Pin_2, // PWM6 (PA2) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.trigger_gpio = GPIOA,
|
|
||||||
.echo_pin = Pin_1, // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
|
||||||
.echo_gpio = GPIOB,
|
|
||||||
.triggerIO = IO_TAG(PA2),
|
|
||||||
.echoIO = IO_TAG(PB1),
|
|
||||||
};
|
};
|
||||||
return &sonarHardware;
|
return &sonarHardware;
|
||||||
#elif defined(UNIT_TEST)
|
#elif defined(UNIT_TEST)
|
||||||
|
@ -128,7 +65,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
|
||||||
#error Sonar not defined for target
|
#error Sonar not defined for target
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
void sonarInit(const sonarHardware_t *sonarHardware)
|
void sonarInit(const sonarHardware_t *sonarHardware)
|
||||||
{
|
{
|
||||||
sonarRange_t sonarRange;
|
sonarRange_t sonarRange;
|
||||||
|
|
|
@ -118,6 +118,9 @@
|
||||||
|
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB0
|
||||||
|
#define SONAR_TRIGGER_PIN PB5
|
||||||
|
|
||||||
#undef GPS
|
#undef GPS
|
||||||
|
|
||||||
#undef BARO
|
#undef BARO
|
||||||
|
|
|
@ -0,0 +1,30 @@
|
||||||
|
|
||||||
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "config/runtime_config.h"
|
||||||
|
#include "config/config.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/sonar.h"
|
||||||
|
|
||||||
|
#ifdef SONAR_CUSTOM_CONFIG
|
||||||
|
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
||||||
|
{
|
||||||
|
static const sonarHardware_t const sonarPWM56 = {
|
||||||
|
.triggerIO = IO_TAG(PB8),
|
||||||
|
.echoIO = IO_TAG(PB9),
|
||||||
|
};
|
||||||
|
static const sonarHardware_t sonarRC78 = {
|
||||||
|
.triggerIO = IO_TAG(PB0),
|
||||||
|
.echoIO = IO_TAG(PB1),
|
||||||
|
};
|
||||||
|
// If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
|
||||||
|
if (feature(FEATURE_SOFTSERIAL)
|
||||||
|
|| feature(FEATURE_RX_PARALLEL_PWM )
|
||||||
|
|| (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) {
|
||||||
|
return &sonarPWM56;
|
||||||
|
} else {
|
||||||
|
return &sonarRC78;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -69,6 +69,8 @@
|
||||||
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_CUSTOM_CONFIG
|
||||||
|
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
|
|
|
@ -184,6 +184,9 @@
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
#define DEFAULT_FEATURES FEATURE_BLACKBOX
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,30 @@
|
||||||
|
|
||||||
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "config/runtime_config.h"
|
||||||
|
#include "config/config.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/sonar.h"
|
||||||
|
|
||||||
|
#ifdef SONAR_CUSTOM_CONFIG
|
||||||
|
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
||||||
|
{
|
||||||
|
static const sonarHardware_t const sonarPWM56 = {
|
||||||
|
.triggerIO = IO_TAG(PB8),
|
||||||
|
.echoIO = IO_TAG(PB9),
|
||||||
|
};
|
||||||
|
static const sonarHardware_t sonarRC78 = {
|
||||||
|
.triggerIO = IO_TAG(PB0),
|
||||||
|
.echoIO = IO_TAG(PB1),
|
||||||
|
};
|
||||||
|
// If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
|
||||||
|
if (feature(FEATURE_SOFTSERIAL)
|
||||||
|
|| feature(FEATURE_RX_PARALLEL_PWM )
|
||||||
|
|| (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) {
|
||||||
|
return &sonarPWM56;
|
||||||
|
} else {
|
||||||
|
return &sonarRC78;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -108,6 +108,7 @@
|
||||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_CUSTOM_CONFIG
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
|
|
|
@ -59,6 +59,8 @@
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
#define USE_USART2
|
#define USE_USART2
|
||||||
|
|
|
@ -0,0 +1,30 @@
|
||||||
|
|
||||||
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "config/runtime_config.h"
|
||||||
|
#include "config/config.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
#include "sensors/sonar.h"
|
||||||
|
|
||||||
|
#ifdef SONAR_CUSTOM_CONFIG
|
||||||
|
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
||||||
|
{
|
||||||
|
static const sonarHardware_t const sonarPWM56 = {
|
||||||
|
.triggerIO = IO_TAG(PB8),
|
||||||
|
.echoIO = IO_TAG(PB9),
|
||||||
|
};
|
||||||
|
static const sonarHardware_t sonarRC78 = {
|
||||||
|
.triggerIO = IO_TAG(PB0),
|
||||||
|
.echoIO = IO_TAG(PB1),
|
||||||
|
};
|
||||||
|
// If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
|
||||||
|
if (feature(FEATURE_SOFTSERIAL)
|
||||||
|
|| feature(FEATURE_RX_PARALLEL_PWM )
|
||||||
|
|| (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) {
|
||||||
|
return &sonarPWM56;
|
||||||
|
} else {
|
||||||
|
return &sonarRC78;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -87,6 +87,8 @@
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_CUSTOM_CONFIG
|
||||||
|
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
|
|
|
@ -52,6 +52,8 @@
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
#define USE_USART2
|
#define USE_USART2
|
||||||
|
|
|
@ -156,6 +156,9 @@
|
||||||
// USART2, PA3
|
// USART2, PA3
|
||||||
#define BIND_PIN PA3
|
#define BIND_PIN PA3
|
||||||
|
|
||||||
|
//#define SONAR
|
||||||
|
//#define SONAR_ECHO_PIN PB1
|
||||||
|
//#define SONAR_TRIGGER_PIN PA2
|
||||||
|
|
||||||
// available IO pins (from schematics)
|
// available IO pins (from schematics)
|
||||||
//#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
//#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15))
|
||||||
|
|
|
@ -61,6 +61,8 @@
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
#define USE_USART2
|
#define USE_USART2
|
||||||
|
|
|
@ -24,9 +24,9 @@
|
||||||
// early prototype had slightly different pin mappings.
|
// early prototype had slightly different pin mappings.
|
||||||
//#define SPRACINGF3MINI_MKII_REVA
|
//#define SPRACINGF3MINI_MKII_REVA
|
||||||
|
|
||||||
#define LED0 PB3
|
#define LED0 PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
|
#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
|
||||||
|
@ -50,7 +50,7 @@
|
||||||
//#define USE_FAKE_ACC
|
//#define USE_FAKE_ACC
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
|
|
||||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||||
|
|
||||||
#define BARO
|
#define BARO
|
||||||
|
@ -64,11 +64,13 @@
|
||||||
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
|
||||||
|
|
||||||
#define SONAR
|
#define SONAR
|
||||||
|
#define SONAR_ECHO_PIN PB1
|
||||||
|
#define SONAR_TRIGGER_PIN PB0
|
||||||
|
|
||||||
#define USB_IO
|
#define USB_IO
|
||||||
#define USB_CABLE_DETECTION
|
#define USB_CABLE_DETECTION
|
||||||
|
|
||||||
#define USB_DETECT_PIN PB5
|
#define USB_DETECT_PIN PB5
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
#define USE_USART1
|
#define USE_USART1
|
||||||
|
|
Loading…
Reference in New Issue