Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Mfoo widesidebars djifixes speedybee f405 #237

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -192,3 +192,4 @@ AP_HW_NeutronRC_H7_BT 2000
# OpenDroneID enabled boards. Use 10000 + the base board ID
AP_HW_CubeOrange_ODID 10140
AP_HW_Pixhawk6_ODID 10053
AP_HW_SpeedyBeeF405WING 1106
Binary file added Tools/bootloaders/SpeedyBeeF405WING_bl.bin
Binary file not shown.
Binary file added Tools/bootloaders/SpeedyBeeF405WING_bl.elf
Binary file not shown.
897 changes: 897 additions & 0 deletions Tools/bootloaders/SpeedyBeeF405WING_bl.hex

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# WS2812 LED
NTF_LED_LEN,4
NTF_LED_TYPES 257
SERVO12_FUNCTION,120

#Serial Port defaults
SERIAL1_PROTOCOL 23
SERIAL4_PROTOCOL -1
SERIAL6_PROTOCOL 2
37 changes: 37 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# hw definition file for processing by chibios_pins.py
# for speedybeef4 bootloader

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1106

# crystal frequency
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0

# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 64

# LEDs
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0)
PA13 LED_ACTIVITY OUTPUT LOW GPIO(1)
define HAL_LED_ON 0

# order of UARTs
SERIAL_ORDER OTG1

PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

DEFAULTGPIO OUTPUT LOW PULLDOWN

# Add CS pins to ensure they are high in bootloader
PA4 MPU_CS CS
PB12 OSD_CS CS
PC14 SDCARD_CS CS
224 changes: 224 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,224 @@
# hw definition file for SpeedyBee F4 WING hardware
# tested on the Speedybee F405 WING board
#

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1106

# crystal frequency
OSCILLATOR_HZ 8000000

define STM32_ST_USE_TIMER 5
define CH_CFG_ST_RESOLUTION 32

# reserve 16k for bootloader, 16k for OSD and 32k for flash storage
FLASH_RESERVE_START_KB 64
FLASH_SIZE_KB 1024

define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 1

# only one I2C bus
I2C_ORDER I2C1

# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6

# LEDs
PA13 LED_GREEN OUTPUT LOW GPIO(0)
PA14 LED_BLUE OUTPUT LOW GPIO(1)

define HAL_GPIO_A_LED_PIN 0
define HAL_GPIO_B_LED_PIN 1

# buzzer
PC15 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0

# spi1 bus for IMU
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA4 MPU_CS CS

# spi2 for OSD
PB13 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
PB12 OSD_CS CS

# spi3 for sdcard
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
PC14 SDCARD_CS CS

# only one I2C bus in normal config
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# analog pins
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
PC4 RSSI_ADC_PIN ADC1 SCALE(1)

PC5 PRESSURE_SENS ADC1 SCALE(1)
define HAL_DEFAULT_AIRSPEED_PIN 15

# define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 11.05 # matched to PDB board
define HAL_BATT_CURR_SCALE 50 # matched to PDB board

# analog rssi pin
define BOARD_RSSI_ANA_PIN 14

# USART1 (ELRS)
PA9 USART1_TX USART1
PA10 USART1_RX USART1


# USART2 (RCIN with inverter)

PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW

# alternative with PA3 as USART2_RX
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA ALT(1)

# USART3 (GPS)
PC10 USART3_TX USART3
PC11 USART3_RX USART3 NODMA

# UART4 serial4
PA0 UART4_TX UART4
PA1 UART4_RX UART4 NODMA

# USART5 (DJI / VTX)
PC12 UART5_TX UART5
PD2 UART5_RX UART5 NODMA

# UART6 (onboard Telemetry)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define HAL_SERIAL6_BAUD 115

# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# PWM out pins. Note that channel order follows the ArduPilot motor
# order conventions
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50)
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52)
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53)
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54)
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55)
PB14 TIM8_CH2N TIM8 PWM(7) GPIO(56)

PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57)
PB10 TIM2_CH3 TIM2 PWM(9) GPIO(58)
PB11 TIM2_CH4 TIM2 PWM(10) GPIO(59)

PB15 TIM1_CH3N TIM1 PWM(11) GPIO(60)
PA8 TIM1_CH1 TIM1 PWM(12) GPIO(61)# LED

# one IMU
IMU Invensensev3 SPI:icm42605 ROTATION_ROLL_180_YAW_270
define HAL_DEFAULT_INS_FAST_SAMPLE 1

# one baro
BARO SPL06 I2C:0:0x76
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_SPL06_ENABLED 1

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# ICM42688P on SPI1
SPIDEV icm42605 SPI1 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ

# OSD on SPI2
SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ

# SD Card on SPI3
SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ

# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"

# setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin

define STM32_PWM_USE_ADVANCED TRUE

# reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE

# save some flash

# disable SMBUS and fuel battery monitors to save flash
define AP_BATTMON_SMBUS_ENABLE 0
define AP_BATTMON_FUEL_ENABLE 0
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
define HAL_BATTMON_INA2XX_ENABLED 0

# disable parachute and sprayer to save flash
define HAL_PARACHUTE_ENABLED 0
define HAL_SPRAYER_ENABLED 0
define AP_GRIPPER_ENABLED 0
define HAL_GENERATOR_ENABLED 0
define AP_ICENGINE_ENABLED 0
#define LANDING_GEAR_ENABLED 0
define WINCH_ENABLED 0
define HAL_ADSB_ENABLED 0

define AC_OAPATHPLANNER_ENABLED 0
define PRECISION_LANDING 0
#define HAL_BARO_WIND_COMP_ENABLED 0
define AP_OPTICALFLOW_ENABLED 0


# Disable un-needed hardware drivers
define HAL_WITH_ESC_TELEM 0
define AP_FETTEC_ONEWIRE_ENABLED 0

define AP_VOLZ_ENABLED 0
define AP_ROBOTISSERVO_ENABLE 0
define HAL_PICCOLO_CAN_ENABLE 0
define HAL_TORQEEDO_ENABLED 0
define HAL_RUNCAM_ENABLED 0
define HAL_HOTT_TELEM_ENABLED 0
define HAL_NMEA_OUTPUT_ENABLED 0
define HAL_BUTTON_ENABLED 0
define AP_NOTIFY_OREOLED_ENABLED 0

#only support MS4525 ANALOG ASP5033 driver
define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0
define AP_AIRSPEED_MS4525_ENABLED 1
define AP_AIRSPEED_ANALOG_ENABLED 1
define AP_AIRSPEED_ASP5033_ENABLED 1

#only support UBLOX and NMEA GPS driver
define AP_GPS_BACKEND_DEFAULT_ENABLED 0
define AP_GPS_UBLOX_ENABLED 1
define AP_GPS_NMEA_ENABLED 1

define AP_TRAMP_ENABLED 1
2 changes: 1 addition & 1 deletion libraries/AP_OSD/AP_OSD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Param: _OPTIONS
// @DisplayName: OSD Options
// @Description: This sets options that change the display
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 19:Right justify TUNED_PN element, 20:Prefix LQ with RF Mode, 21:One decimal attitude, 22:One decimal throttle, 23:Shorten Pluscode
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows, 17:wide Sidebar, 18:Two decimal vertical speed, 19:Right justify TUNED_PN element, 20:Prefix LQ with RF Mode, 21:One decimal attitude, 22:One decimal throttle, 23:Shorten Pluscode
// @User: Standard
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK | OPTION_ONE_DECIMAL_ATTITUDE | OPTION_RF_MODE_ALONG_WITH_LQ | OPTION_RIGHT_JUSTIFY_TUNED_PN ),

Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -314,11 +314,14 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen
#if HAL_PLUSCODE_ENABLE
void draw_pluscode(uint8_t x, uint8_t y);
#endif

//helper functions
void draw_speed(uint8_t x, uint8_t y, bool available, float magnitude = 0, bool blink = false);
void draw_speed_with_arrow(uint8_t x, uint8_t y, float angle_rad, float magnitude, bool blink = false);
void draw_distance(uint8_t x, uint8_t y, float distance, bool can_only_be_positive = true, bool available = true);
void draw_temperature(uint8_t x, uint8_t y, bool available, float value = 0, bool blink = false);
char get_arrow_font_index (int32_t angle_cd);

#if HAL_WITH_ESC_TELEM
void draw_highest_esc_temp(uint8_t x, uint8_t y);
void draw_rpm(uint8_t x, uint8_t y, float rpm); // helper
Expand Down Expand Up @@ -631,6 +634,8 @@ class AP_OSD
OPTION_INVERTED_AH_ROLL = 1U<<2,
OPTION_IMPERIAL_MILES = 1U<<3,
OPTION_DISABLE_CROSSHAIR = 1U<<4,
OPTION_BF_ARROWS = 1U<<5,
OPTION_WIDE_SIDEBAR = 1U<<17,
OPTION_TWO_DECIMALS_VERTICAL_SPEED = 1U<<18,
OPTION_RIGHT_JUSTIFY_TUNED_PN = 1U<<19,
OPTION_RF_MODE_ALONG_WITH_LQ = 1U<<20,
Expand Down
30 changes: 15 additions & 15 deletions libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,13 +56,13 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend
static const uint8_t SYM_FS = 0x99;
static const uint8_t SYM_KMH = 0x9E;
static const uint8_t SYM_MPH = 0x9D;
static const uint8_t SYM_DEGR = 0x1D;
static const uint8_t SYM_DEGR = 0x08;
static const uint8_t SYM_PCNT = 0x25;
static const uint8_t SYM_RPM = 0x12;
static const uint8_t SYM_ASPD = 0x41;
static const uint8_t SYM_GSPD = 0x70;
static const uint8_t SYM_WSPD = 0x1B;
static const uint8_t SYM_VSPD = 0x7F;
static const uint8_t SYM_GSPD = 0x47;
static const uint8_t SYM_WSPD = 0x57;
static const uint8_t SYM_VSPD = 0x5E;
static const uint8_t SYM_WPNO = 0x23;
static const uint8_t SYM_WPDIR = 0xE6;
static const uint8_t SYM_WPDST = 0xE7;
Expand All @@ -71,10 +71,10 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend

static const uint8_t SYM_SAT_L = 0x1E;
static const uint8_t SYM_SAT_R = 0x1F;
static const uint8_t SYM_HDOP_L = 0x11;
static const uint8_t SYM_HDOP_R = 0x08;
static const uint8_t SYM_HDOP_L = 0x48;
static const uint8_t SYM_HDOP_R = 0x44;

static const uint8_t SYM_HOME = 0x05;
static const uint8_t SYM_HOME = 0x11;
static const uint8_t SYM_WIND = 0x57;

static const uint8_t SYM_ARROW_START = 0x60;
Expand Down Expand Up @@ -103,30 +103,30 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend

static const uint8_t SYM_DEGREES_C = 0x0E;
static const uint8_t SYM_DEGREES_F = 0x0D;
static const uint8_t SYM_GPS_LAT = 0x68;
static const uint8_t SYM_GPS_LONG = 0x6C;
static const uint8_t SYM_ARMED = 0x08;
static const uint8_t SYM_DISARMED = 0x08;
static const uint8_t SYM_GPS_LAT = 0x89;
static const uint8_t SYM_GPS_LONG = 0x98;
static const uint8_t SYM_ARMED = 0x00;
static const uint8_t SYM_DISARMED = 0x2A;
static const uint8_t SYM_ROLL0 = 0x2D;
static const uint8_t SYM_ROLLR = 0x64;
static const uint8_t SYM_ROLLL = 0x6C;
static const uint8_t SYM_PTCH0 = 0x7C;
static const uint8_t SYM_PTCHUP = 0x68;
static const uint8_t SYM_PTCHDWN = 0x60;
static const uint8_t SYM_XERR = 0xEE;
static const uint8_t SYM_XERR = 0x21;
static const uint8_t SYM_KN = 0xF0;
static const uint8_t SYM_NM = 0xF1;
static const uint8_t SYM_DIST = 0x22;
static const uint8_t SYM_DIST = 0x04;
static const uint8_t SYM_FLY = 0x9C;
static const uint8_t SYM_EFF = 0xF2;
static const uint8_t SYM_AH = 0xF3;
static const uint8_t SYM_MW = 0xF4;
static const uint8_t SYM_CLK = 0x08;
static const uint8_t SYM_KILO = 0x4B;
static const uint8_t SYM_TERALT = 0xEF;
static const uint8_t SYM_TERALT = 0x7F;
static const uint8_t SYM_FENCE_ENABLED = 0xF5;
static const uint8_t SYM_FENCE_DISABLED = 0xF6;
static const uint8_t SYM_RNGFD = 0x72;
static const uint8_t SYM_RNGFD = 0x7F;
static const uint8_t SYM_LQ = 0xF8;

static constexpr uint8_t symbols[AP_OSD_NUM_SYMBOLS] {
Expand Down
Loading
Loading