Skip to content

Commit

Permalink
CxPilot_V5.0.1 : Version and Release Notes Update
Browse files Browse the repository at this point in the history
 + HWDEF changes as per Ottano/dev


WIP
  • Loading branch information
Pradeep-Carbonix committed Nov 22, 2023
1 parent 78d82a8 commit 08b345c
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 10 deletions.
10 changes: 10 additions & 0 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,13 @@
Release 5.0.1 20th Nov 2023
---------------------------
Changes since 4.3.8:
- AP_BattMonitor: Addition of AD7091R5 ADC I2C Read Driver #23564
- AP_Compass: Add in QMC5883P driver #25230
- Carbonix PR - AP_BattMonitor: Add in reventech fuel level driver #25219
- WIP: Hirth Engine Integration #21805
- feature/OV3-1018-enable-ardupilot-apd-implementation-in-hwdef


Release 4.3.8 24th August 2023
------------------------------

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@ APJ_BOARD_ID 1064
# setup build for a peripheral firmware
env AP_PERIPH 1

# crystal frequency set to 0 to use internal clock
OSCILLATOR_HZ 0
# crystal frequency set to 0 to use internal clock; currently configured for external crystal 12MHZ
OSCILLATOR_HZ 12000000

# assume 1024K flash part
FLASH_SIZE_KB 1024
Expand Down
25 changes: 17 additions & 8 deletions libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ APJ_BOARD_ID 1064
# setup build for a peripheral firmware
env AP_PERIPH 1

# crystal frequency set to 0 to use internal clock
OSCILLATOR_HZ 0
# crystal frequency set to 12MHz to use internal clock
OSCILLATOR_HZ 12000000

#MCU F405 Flash 1024
FLASH_SIZE_KB 1024
Expand Down Expand Up @@ -132,17 +132,26 @@ define HAL_PERIPH_GPS_PORT_DEFAULT 2
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY

# default ADSB off by setting 0 baudrate
define HAL_PERIPH_ENABLE_ADSB
define HAL_PERIPH_ADSB_PORT_DEFAULT 3
define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
# define HAL_PERIPH_ENABLE_ADSB
# define HAL_PERIPH_ADSB_PORT_DEFAULT 3
# define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600

BARO MS56XX I2C:0:0x76
COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE
define HAL_PERIPH_ARM_MONITORING_ENABLE 1

define AP_COMPASS_QMC5883P_ENABLED 1
BARO MS56XX I2C:0:0x76
COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180

#GPS Compass Enable
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE

# enable Rangefinder
define HAL_PERIPH_ENABLE_RANGEFINDER 1

define HAL_PERIPH_ENABLE_BATTERY 1

define HAL_PERIPH_ENABLE_ESC_APD 1
define APD_ESC_INSTANCES 4

define AP_CUSTOM_FIRMWARE_STRING "CxPilot_V5.0.1"

7 changes: 7 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,10 @@
MCU STM32H7xx STM32H743xx

include hwdef.inc

define AP_CUSTOM_FIRMWARE_STRING "CxPilot_V5.0.1"

define HAL_EFI_ENABLED 1
define AP_EFI_SERIAL_HIRTH_ENABLED 1
define AP_EFI_THROTTLE_LINEARISATION_ENABLED 1
define AP_ICENGINE_TCA9554_STARTER_ENABLED 1

0 comments on commit 08b345c

Please sign in to comment.