forked from Archive/PX4-Autopilot
[DO NOT MERGE] boards: mro_pixracerpro remap GPS1 to 4xPWM/DSHOT
This commit is contained in:
parent
bd17653383
commit
0c19fabbd7
|
@ -8,68 +8,68 @@ px4_add_board(
|
|||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
UAVCAN_INTERFACES 2
|
||||
#UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
#SPARE:/dev/ttyS0
|
||||
TEL1:/dev/ttyS1
|
||||
TEL2:/dev/ttyS2
|
||||
GPS1:/dev/ttyS3
|
||||
#RC:/dev/ttyS4
|
||||
#CONSOLE:/dev/ttyS5
|
||||
#FRSKY:/dev/ttyS6
|
||||
#RC:/dev/ttyS3
|
||||
#CONSOLE:/dev/ttyS4
|
||||
#FRSKY:/dev/ttyS5
|
||||
DRIVERS
|
||||
adc/ads1115
|
||||
#adc/ads1115
|
||||
adc/board_adc
|
||||
#barometer # all available barometer drivers
|
||||
barometer/dps310
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#batt_smbus
|
||||
#camera_capture
|
||||
#camera_trigger
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
#distance_sensor # all available distance sensor drivers
|
||||
distance_sensor/tfmini
|
||||
dshot
|
||||
gps
|
||||
#gps
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm20602
|
||||
imu/invensense/icm20948
|
||||
irlock
|
||||
lights # all available light drivers
|
||||
magnetometer # all available magnetometer drivers
|
||||
optical_flow # all available optical flow drivers
|
||||
osd
|
||||
pca9685
|
||||
pca9685_pwm_out
|
||||
power_monitor/ina226
|
||||
#irlock
|
||||
#lights # all available light drivers
|
||||
#magnetometer # all available magnetometer drivers
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
#pca9685
|
||||
#pca9685_pwm_out
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
#pwm_out_sim
|
||||
#pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
rpm
|
||||
smart_battery/batmon
|
||||
telemetry # all available telemetry drivers
|
||||
#roboclaw
|
||||
#rpm
|
||||
#smart_battery/batmon
|
||||
#telemetry # all available telemetry drivers
|
||||
tone_alarm
|
||||
uavcan
|
||||
#uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
#airspeed_selector
|
||||
#attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
#camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
esc_battery
|
||||
#esc_battery
|
||||
events
|
||||
flight_mode_manager
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
#fw_att_control
|
||||
#fw_pos_control_l1
|
||||
gyro_calibration
|
||||
gyro_fft
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
#landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
|
@ -79,14 +79,14 @@ px4_add_board(
|
|||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
#rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
uuv_att_control
|
||||
uuv_pos_control
|
||||
vmount
|
||||
vtol_att_control
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#uuv_att_control
|
||||
#uuv_pos_control
|
||||
#vmount
|
||||
#vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
dmesg
|
||||
|
@ -94,7 +94,7 @@ px4_add_board(
|
|||
esc_calib
|
||||
gpio
|
||||
hardfault_log
|
||||
i2cdetect
|
||||
#i2cdetect
|
||||
led_control
|
||||
mft
|
||||
mixer
|
||||
|
@ -118,7 +118,7 @@ px4_add_board(
|
|||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fake_gps
|
||||
#fake_gps
|
||||
#fake_imu
|
||||
#fake_magnetometer
|
||||
#fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
|
|
|
@ -234,9 +234,6 @@
|
|||
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
|
||||
|
||||
#define GPIO_USART6_TX 0 /* USART6 is RX-only */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
|
||||
|
@ -273,8 +270,3 @@
|
|||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_1) /* PG13 */
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_1 /* PG12 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
|
|
@ -76,8 +76,6 @@ CONFIG_GRAN=y
|
|||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
|
@ -165,9 +163,6 @@ CONFIG_STM32H7_DMA1=y
|
|||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
|
@ -192,7 +187,6 @@ CONFIG_STM32H7_SPI_DMATHRESHOLD=8
|
|||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=y
|
||||
|
@ -208,9 +202,6 @@ CONFIG_SYSTEM_NSH=y
|
|||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGSTP=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||
|
|
|
@ -83,8 +83,8 @@
|
|||
#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN6)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 4
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 4
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_nPOWER_IN_A /* PB5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
|
@ -118,7 +118,7 @@
|
|||
#define GPIO_PPM_IN /* PB0 T3C3 */ GPIO_TIM3_CH3IN_1
|
||||
|
||||
/* RC Serial port */
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
#define RC_SERIAL_PORT "/dev/ttyS3"
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
#define GPIO_RSSI_IN /* PC1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
|
@ -147,8 +147,8 @@
|
|||
#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
|
||||
#define BOARD_NUM_IO_TIMERS 2
|
||||
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
|
||||
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
|
|
@ -33,6 +33,4 @@
|
|||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
};
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {};
|
||||
|
|
|
@ -34,20 +34,15 @@
|
|||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer8, DMA{DMA::Index1}),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortB, GPIO::Pin8}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortB, GPIO::Pin9}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
|
|
|
@ -37,6 +37,8 @@
|
|||
* I2C interface for DPS310
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
#include <lib/drivers/device/i2c.h>
|
||||
|
||||
namespace dps310
|
||||
|
@ -89,3 +91,5 @@ DPS310_I2C::write(unsigned address, void *data, unsigned count)
|
|||
}
|
||||
|
||||
} // namespace dps310
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
|
|
|
@ -36,7 +36,9 @@
|
|||
namespace dps310
|
||||
{
|
||||
extern device::Device *DPS310_SPI_interface(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
|
||||
#if defined(CONFIG_I2C)
|
||||
extern device::Device *DPS310_I2C_interface(uint8_t bus, uint32_t device, int bus_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
}
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
|
@ -59,12 +61,16 @@ I2CSPIDriverBase *DPS310::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
{
|
||||
device::Device *interface = nullptr;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (config.bus_type == BOARD_I2C_BUS) {
|
||||
interface = DPS310_I2C_interface(config.bus, config.i2c_address, config.bus_frequency);
|
||||
|
||||
} else if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = DPS310_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
} else
|
||||
#endif // CONFIG_I2C
|
||||
if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = DPS310_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
|
||||
if (interface == nullptr) {
|
||||
PX4_ERR("failed creating interface for bus %i (devid 0x%" PRIx32 ")", config.bus, config.spi_devid);
|
||||
|
@ -95,9 +101,15 @@ I2CSPIDriverBase *DPS310::instantiate(const I2CSPIDriverConfig &config, int runt
|
|||
extern "C" int dps310_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = DPS310;
|
||||
BusCLIArguments cli{true, true};
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
BusCLIArguments cli {true, true};
|
||||
cli.i2c_address = 0x77;
|
||||
cli.default_i2c_frequency = 400000;
|
||||
#else
|
||||
BusCLIArguments cli {false, true};
|
||||
#endif // CONFIG_I2C
|
||||
|
||||
cli.default_spi_frequency = 10 * 1000 * 1000;
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
|
|
@ -49,15 +49,17 @@ px4_add_module(
|
|||
drivers_magnetometer
|
||||
)
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__imu__invensense__icm20948_i2c_passthrough
|
||||
MAIN icm20948_i2c_passthrough
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ICM20948_I2C_Passthrough.cpp
|
||||
ICM20948_I2C_Passthrough.hpp
|
||||
icm20948_i2c_passthrough_main.cpp
|
||||
InvenSense_ICM20948_registers.hpp
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
)
|
||||
if(CONFIG_I2C)
|
||||
px4_add_module(
|
||||
MODULE drivers__imu__invensense__icm20948_i2c_passthrough
|
||||
MAIN icm20948_i2c_passthrough
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ICM20948_I2C_Passthrough.cpp
|
||||
ICM20948_I2C_Passthrough.hpp
|
||||
icm20948_i2c_passthrough_main.cpp
|
||||
InvenSense_ICM20948_registers.hpp
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
)
|
||||
endif()
|
||||
|
|
|
@ -43,7 +43,6 @@
|
|||
#include "AKM_AK09916_registers.hpp"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/drivers/device/i2c.h>
|
||||
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
|
|
Loading…
Reference in New Issue