forked from Archive/PX4-Autopilot
boards: update id string from V5X{0-a}{0-a} to V5X{xxxx}{xxxx}
boards: new format for hwtypecmp string boards: update manifest.c to follow the new hw_ver_rev format
This commit is contained in:
parent
49d63958a8
commit
ec1614d156
|
@ -115,9 +115,7 @@
|
|||
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
|
||||
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
|
||||
#define HW_INFO_INIT {'V','5','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
#define HW_INFO_INIT "V5%04x%04x"
|
||||
|
||||
#define BOARD_TAP_ESC_MODE 2 // select closed-loop control mode for the esc
|
||||
// #define BOARD_USE_ESC_CURRENT_REPORT
|
||||
|
|
|
@ -83,9 +83,7 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PB1 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_HW_REV_SENSE /* PA0 */ ADC1_GPIO(0)
|
||||
#define GPIO_HW_VER_SENSE /* PA1 */ ADC1_GPIO(1)
|
||||
#define HW_INFO_INIT {'C','A','N','G','P','S','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 6
|
||||
#define HW_INFO_INIT_REV 7
|
||||
#define HW_INFO_INIT "CANGPS%04x%04x"
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
|
|
|
@ -104,7 +104,7 @@ static const px4_hw_mft_item_t hw_mft_list_v0000[] = {
|
|||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver/rev
|
||||
{0x0000, hw_mft_list_v0000, arraySize(hw_mft_list_v0000)},
|
||||
{0x00000000, hw_mft_list_v0000, arraySize(hw_mft_list_v0000)},
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -127,7 +127,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -138,7 +138,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -152,14 +152,12 @@
|
|||
#define GPIO_HW_REV_SENSE /* PC3 */ GPIO_ADC12_INP13
|
||||
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_VER_SENSE /* PC2 */ GPIO_ADC123_INP12
|
||||
#define HW_INFO_INIT {'V','D','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
#define HW_INFO_INIT "VD%04x%04x"
|
||||
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2
|
||||
|
||||
#define VD00 HW_VER_REV(0x0,0x0) // Durandal, Ver 0 Rev 0
|
||||
#define VD01 HW_VER_REV(0x0,0x1) // Durandal, Ver 0 Rev 1
|
||||
#define VD00000000 HW_VER_REV(0x0,0x0) // Durandal, Ver 0 Rev 0
|
||||
#define VD00000001 HW_VER_REV(0x0,0x1) // Durandal, Ver 0 Rev 1
|
||||
|
||||
/* CAN Silence
|
||||
*
|
||||
|
|
|
@ -83,8 +83,8 @@ static const px4_hw_mft_item_t hw_mft_list_durandal[] = {
|
|||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver_rev
|
||||
{VD00, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
{VD01, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
{VD00000000, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
{VD00000001, hw_mft_list_durandal, arraySize(hw_mft_list_durandal)},
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -107,7 +107,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -118,7 +118,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -185,9 +185,8 @@
|
|||
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
|
||||
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
|
||||
#define HW_INFO_INIT {'V','5','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
#define HW_INFO_INIT "V5%04x%04x"
|
||||
|
||||
/* CAN Silence
|
||||
*
|
||||
* Silent mode control \ ESC Mux select
|
||||
|
|
|
@ -129,8 +129,8 @@ static const px4_hw_mft_item_t hw_mft_list_v0540[] = {
|
|||
};
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
|
||||
{0x0400, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
|
||||
{0x00000000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
|
||||
{0x00040000, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -153,7 +153,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -164,7 +164,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -142,9 +142,7 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
|
||||
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
|
||||
#define HW_INFO_INIT {'V','1','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2 /* Offset in above string of the VER */
|
||||
#define HW_INFO_INIT_REV 3 /* Offset in above string of the REV */
|
||||
#define HW_INFO_INIT "V1%04x%04x"
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
|
|
|
@ -90,8 +90,8 @@ static const px4_hw_mft_item_t hw_mft_list_fc0100[] = {
|
|||
};
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{0x0006, hw_mft_list_fc0006, arraySize(hw_mft_list_fc0006)},
|
||||
{0x0100, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}
|
||||
{0x00000006, hw_mft_list_fc0006, arraySize(hw_mft_list_fc0006)},
|
||||
{0x00010000, hw_mft_list_fc0100, arraySize(hw_mft_list_fc0100)}
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -114,7 +114,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -125,7 +125,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -182,9 +182,7 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
|
||||
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
|
||||
#define HW_INFO_INIT {'V','2','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
|
||||
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
|
||||
#define HW_INFO_INIT "V2%04x%04x"
|
||||
|
||||
/* PE6 is nARMED --> FCv2 this goes to TP13
|
||||
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
|
||||
|
|
|
@ -83,7 +83,7 @@ static const px4_hw_mft_item_t hw_mft_list_fc0200[] = {
|
|||
};
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{0x0300, hw_mft_list_fc0200, arraySize(hw_mft_list_fc0200)},
|
||||
{0x00030000, hw_mft_list_fc0200, arraySize(hw_mft_list_fc0200)},
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -106,7 +106,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -117,7 +117,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -192,9 +192,8 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* GPIO_AD_B0_01 GPIO1_IO01 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | HW_IOMUX)
|
||||
#define GPIO_HW_REV_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24)
|
||||
#define GPIO_HW_VER_SENSE /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20)
|
||||
#define HW_INFO_INIT {'V','5','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
#define HW_INFO_INIT "V5%04x%04x"
|
||||
|
||||
/* CAN Silence
|
||||
*
|
||||
* Silent mode control \ ESC Mux select
|
||||
|
|
|
@ -9,9 +9,9 @@ param set-default BAT2_V_DIV 18.1
|
|||
param set-default BAT1_A_PER_V 36.367515152
|
||||
param set-default BAT2_A_PER_V 36.367515152
|
||||
|
||||
if ver hwtypecmp V550 V552 V560 V562
|
||||
if ver hwtypecmp V500050000 V500050002 V500060000 V500060002
|
||||
then
|
||||
# CUAV V5+ (V550/V552) and V5nano (V560/V562) have 3 IMUs
|
||||
# CUAV V5+ (V500050000/V500050002) and V5nano (V560/V562) have 3 IMUs
|
||||
# Multi-EKF (IMUs only)
|
||||
param set-default EKF2_MULTI_IMU 3
|
||||
param set-default SENS_IMU_MODE 0
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
board_adc start
|
||||
|
||||
if ver hwtypecmp V552 V562
|
||||
if ver hwtypecmp V500050002 V500060002
|
||||
then
|
||||
# Internal SPI bus ICM-42688-P
|
||||
icm42688p -s -R 2 -q start
|
||||
|
|
|
@ -188,17 +188,15 @@
|
|||
#define GPIO_HW_REV_SENSE /* PC3 */ ADC1_GPIO(13)
|
||||
#define GPIO_HW_VER_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_VER_SENSE /* PC2 */ ADC1_GPIO(12)
|
||||
#define HW_INFO_INIT {'V','5','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 2
|
||||
#define HW_INFO_INIT_REV 3
|
||||
#define HW_INFO_INIT "V5%04x%04x"
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 3
|
||||
#define V500 HW_VER_REV(0x0,0x0) // FMUV5, Rev 0
|
||||
#define V515 HW_VER_REV(0x1,0x5) // CUAV V5, Rev 5
|
||||
#define V540 HW_VER_REV(0x4,0x0) // HolyBro mini no can 2,3, Rev 0
|
||||
#define V550 HW_VER_REV(0x5,0x0) // CUAV V5+, Rev 0
|
||||
#define V552 HW_VER_REV(0x5,0x2) // CUAV V5+ ICM42688P, Rev 2
|
||||
#define V560 HW_VER_REV(0x6,0x0) // CUAV V5nano with can 2, Rev 0
|
||||
#define V562 HW_VER_REV(0x6,0x2) // CUAV V5nano ICM42688P, Rev 2
|
||||
#define V500000000 HW_VER_REV(0x0,0x0) // FMUV5, Rev 0
|
||||
#define V500010005 HW_VER_REV(0x1,0x5) // CUAV V5, Rev 5
|
||||
#define V500040000 HW_VER_REV(0x4,0x0) // HolyBro mini no can 2,3, Rev 0
|
||||
#define V500050000 HW_VER_REV(0x5,0x0) // CUAV V5+, Rev 0
|
||||
#define V500050002 HW_VER_REV(0x5,0x2) // CUAV V5+ ICM42688P, Rev 2
|
||||
#define V500060000 HW_VER_REV(0x6,0x0) // CUAV V5nano with can 2, Rev 0
|
||||
#define V500060002 HW_VER_REV(0x6,0x2) // CUAV V5nano ICM42688P, Rev 2
|
||||
|
||||
/* CAN Silence
|
||||
*
|
||||
|
|
|
@ -157,13 +157,13 @@ static const px4_hw_mft_item_t hw_mft_list_v0600[] = {
|
|||
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{V500, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
|
||||
{V515, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5 R:5 V:1
|
||||
{V540, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
|
||||
{V550, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5+ R:0 V:5
|
||||
{V552, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5+ R:2 V:5 ICM42688P
|
||||
{V560, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // CUAV V5nano R:0 V:6 with can 2
|
||||
{V562, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5nano R:2 V:6 ICM42688P
|
||||
{V500000000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
|
||||
{V500010005, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5 R:5 V:1
|
||||
{V500040000, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)}, // HolyBro mini no can 2,3
|
||||
{V500050000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5+ R:0 V:5
|
||||
{V500050002, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5+ R:2 V:5 ICM42688P
|
||||
{V500060000, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // CUAV V5nano R:0 V:6 with can 2
|
||||
{V500060002, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // Alias for CUAV V5nano R:2 V:6 ICM42688P
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -186,7 +186,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -197,7 +197,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
|
||||
initSPIHWVersion(V500, {
|
||||
initSPIHWVersion(V500000000, {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortF, GPIO::Pin3}, SPI::DRDY{GPIO::PortC, GPIO::Pin5}),
|
||||
|
@ -61,7 +61,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
|
|||
}),
|
||||
}),
|
||||
|
||||
initSPIHWVersion(V552, {
|
||||
initSPIHWVersion(V500050002, {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortF, GPIO::Pin11}, SPI::DRDY{GPIO::PortC, GPIO::Pin5}),
|
||||
|
@ -86,7 +86,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
|
|||
}),
|
||||
}),
|
||||
|
||||
initSPIHWVersion(V562, {
|
||||
initSPIHWVersion(V500060002, {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20689, SPI::CS{GPIO::PortF, GPIO::Pin2}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortF, GPIO::Pin11}, SPI::DRDY{GPIO::PortC, GPIO::Pin5}),
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
if ver hwtypecmp V5X90 V5X91 V5Xa0 V5Xa1 V5X80 V5X81
|
||||
if ver hwtypecmp V5X00090000 V5X00090001 V5X000a0000 V5X000a0001 V5X00080000 V5X00080001
|
||||
then
|
||||
# Start MAVLink on the UART connected to the mission computer
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
|
|
|
@ -48,11 +48,11 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwtypecmp V5X90 V5X91 V5X92 V5Xa0 V5Xa1 V5Xa2
|
||||
if ver hwtypecmp V5X00090000 V5X00090001 V5X00090002 V5X000a0000 V5X000a0001 V5X000a0002 V5X00080000 V5X00080001 V5X00080002
|
||||
then
|
||||
#SKYNODE base fmu board orientation
|
||||
|
||||
if ver hwtypecmp V5X90 V5X91 V5Xa0 V5Xa1
|
||||
if ver hwtypecmp V5X00090000 V5X00090001 V5X000a0000 V5X000a0001 V5X00080000 V5X00080001
|
||||
then
|
||||
# Internal SPI BMI088
|
||||
bmi088 -A -R 2 -s start
|
||||
|
@ -74,7 +74,7 @@ then
|
|||
else
|
||||
#FMUv5Xbase board orientation
|
||||
|
||||
if ver hwtypecmp V5X00 V5X01
|
||||
if ver hwtypecmp V5X00000000 V5X00000001
|
||||
then
|
||||
# Internal SPI BMI088
|
||||
bmi088 -A -R 4 -s start
|
||||
|
@ -104,7 +104,7 @@ ist8310 -X -b 1 -R 10 start
|
|||
if param compare SENS_INT_BARO_EN 1
|
||||
then
|
||||
bmp388 -I -a 0x77 start
|
||||
if ver hwtypecmp V5X00 V5X90 V5Xa0
|
||||
if ver hwtypecmp V5X00000000 V5X00010000 V5X00080000 V5X00090000 V5X000a0000
|
||||
then
|
||||
bmp388 -I start
|
||||
else
|
||||
|
|
|
@ -184,24 +184,22 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PF5 */ ADC3_GPIO(15)
|
||||
#define GPIO_HW_VER_SENSE /* PF4 */ ADC3_GPIO(14)
|
||||
#define HW_INFO_INIT {'V','5','X','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
|
||||
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
|
||||
#define HW_INFO_INIT "V5X%04x%04x"
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 6
|
||||
// Base FMUM
|
||||
#define V5X00 HW_VER_REV(0x0,0x0) // FMUV5X, Rev 0
|
||||
#define V5X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
|
||||
#define V5X01 HW_VER_REV(0x0,0x1) // FMUV5X I2C2 BMP388, Rev 1
|
||||
#define V5X02 HW_VER_REV(0x0,0x2) // FMUV5X, Rev 2
|
||||
#define V5X50 HW_VER_REV(0x5,0x0) // FMUV5X, HB Mini Rev 0
|
||||
#define V5X51 HW_VER_REV(0x5,0x1) // FMUV5X I2C2 BMP388, HB Mini Rev 1
|
||||
#define V5X52 HW_VER_REV(0x5,0x2) // FMUV5X, HB Mini Rev 2
|
||||
#define V5X90 HW_VER_REV(0x9,0x0) // NO USB, Rev 0
|
||||
#define V5X91 HW_VER_REV(0x9,0x1) // NO USB I2C2 BMP388, Rev 1
|
||||
#define V5X92 HW_VER_REV(0x9,0x2) // NO USB I2C2 BMP388, Rev 2
|
||||
#define V5Xa0 HW_VER_REV(0xa,0x0) // NO USB (Q), Rev 0
|
||||
#define V5Xa1 HW_VER_REV(0xa,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
|
||||
#define V5Xa2 HW_VER_REV(0xa,0x2) // NO USB (Q) I2C2 BMP388, Rev 2
|
||||
#define V5X00000000 HW_VER_REV(0x0,0x0) // FMUV5X, Rev 0
|
||||
#define V5X00010000 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
|
||||
#define V5X00000001 HW_VER_REV(0x0,0x1) // FMUV5X I2C2 BMP388, Rev 1
|
||||
#define V5X00000002 HW_VER_REV(0x0,0x2) // FMUV5X, Rev 2
|
||||
#define V5X00050000 HW_VER_REV(0x5,0x0) // FMUV5X, HB Mini Rev 0
|
||||
#define V5X00050001 HW_VER_REV(0x5,0x1) // FMUV5X I2C2 BMP388, HB Mini Rev 1
|
||||
#define V5X00050002 HW_VER_REV(0x5,0x2) // FMUV5X, HB Mini Rev 2
|
||||
#define V5X00090000 HW_VER_REV(0x9,0x0) // NO USB, Rev 0
|
||||
#define V5X00090001 HW_VER_REV(0x9,0x1) // NO USB I2C2 BMP388, Rev 1
|
||||
#define V5X00090002 HW_VER_REV(0x9,0x2) // NO USB I2C2 BMP388, Rev 2
|
||||
#define V5X000a0000 HW_VER_REV(0xa,0x0) // NO USB (Q), Rev 0
|
||||
#define V5X000a0001 HW_VER_REV(0xa,0x1) // NO USB (Q) I2C2 BMP388, Rev 1
|
||||
#define V5X000a0002 HW_VER_REV(0xa,0x2) // NO USB (Q) I2C2 BMP388, Rev 2
|
||||
|
||||
#define UAVCAN_NUM_IFACES_RUNTIME 1
|
||||
|
||||
|
|
|
@ -159,19 +159,19 @@ static const px4_hw_mft_item_t hw_mft_list_v0509[] = {
|
|||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver_rev
|
||||
{V5X00, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 0
|
||||
{V5X01, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 1
|
||||
{V5X02, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 2
|
||||
{V5X10, hw_mft_list_v0510, arraySize(hw_mft_list_v0510)}, // NO PX4IO, Rev 0
|
||||
{V5X50, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 0
|
||||
{V5X51, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 1
|
||||
{V5X52, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 2
|
||||
{V5X90, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB, Rev 0
|
||||
{V5X91, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 1
|
||||
{V5X92, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 2
|
||||
{V5Xa0, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q), Rev 0
|
||||
{V5Xa1, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 1
|
||||
{V5Xa2, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 2
|
||||
{V5X00000000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 0
|
||||
{V5X00000001, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 1
|
||||
{V5X00000002, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)}, // FMUV5X, Rev 2
|
||||
{V5X00010000, hw_mft_list_v0510, arraySize(hw_mft_list_v0510)}, // NO PX4IO, Rev 0
|
||||
{V5X00050000, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 0
|
||||
{V5X00050001, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 1
|
||||
{V5X00050002, hw_mft_list_v0550, arraySize(hw_mft_list_v0550)}, // FMUV5X, HB Mini Rev 2
|
||||
{V5X00090000, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB, Rev 0
|
||||
{V5X00090001, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 1
|
||||
{V5X00090002, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB I2C2 BMP388, Rev 2
|
||||
{V5X000a0000, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q), Rev 0
|
||||
{V5X000a0001, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 1
|
||||
{V5X000a0002, hw_mft_list_v0509, arraySize(hw_mft_list_v0509)}, // NO USB (Q) I2C2 BMP388, Rev 2
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -194,7 +194,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -205,7 +205,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -173,9 +173,7 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
|
||||
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
|
||||
#define HW_INFO_INIT {'V','6','U','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
|
||||
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
|
||||
#define HW_INFO_INIT "V6U%04x%04x"
|
||||
|
||||
/* HEATER
|
||||
* PWM in future
|
||||
|
|
|
@ -82,7 +82,7 @@ static const px4_hw_mft_item_t hw_mft_list_v0600[] = {
|
|||
};
|
||||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
{0x0000, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
|
||||
{0x00000000, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -105,7 +105,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -116,7 +116,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#------------------------------------------------------------------------------
|
||||
set HAVE_PM2 yes
|
||||
|
||||
if ver hwtypecmp V6X50 V6X51 V6X53 V6X54
|
||||
if ver hwtypecmp V6X00050000 V6X00050001 V6X00050003 V6X00050004
|
||||
then
|
||||
set HAVE_PM2 no
|
||||
fi
|
||||
|
@ -47,7 +47,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwtypecmp V6X04 V6X14 V6X54
|
||||
if ver hwtypecmp V6X00000004 V6X00010004 V6X00050004
|
||||
then
|
||||
# Internal SPI bus ICM20649
|
||||
icm20649 -s -R 6 start
|
||||
|
@ -60,7 +60,7 @@ fi
|
|||
# Internal SPI bus ICM42688p
|
||||
icm42688p -R 6 -s start
|
||||
|
||||
if ver hwtypecmp V6X03 V6X13 V6X04 V6X14 V6X53 V6X54
|
||||
if ver hwtypecmp V6X00000003 V6X00010003 V6X00000004 V6X00010004 V6X00050003 V6X00050004
|
||||
then
|
||||
# Internal SPI bus ICM-42670-P (hard-mounted)
|
||||
icm42670p -R 10 -s start
|
||||
|
@ -78,7 +78,7 @@ ist8310 -X -b 1 -R 10 start
|
|||
# Possible internal Baro
|
||||
bmp388 -I -a 0x77 start
|
||||
|
||||
if ver hwtypecmp V6X00 V6X10
|
||||
if ver hwtypecmp V6X00000000 V6X00010000
|
||||
then
|
||||
bmp388 -I start
|
||||
else
|
||||
|
|
|
@ -211,23 +211,21 @@
|
|||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
|
||||
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
|
||||
#define HW_INFO_INIT {'V','6','X','x', 'x',0}
|
||||
#define HW_INFO_INIT_VER 3 /* Offset in above string of the VER */
|
||||
#define HW_INFO_INIT_REV 4 /* Offset in above string of the REV */
|
||||
#define HW_INFO_INIT "V6X%04x%04x"
|
||||
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 6 // Rev 0 and Rev 3,4 Sensor sets
|
||||
// Base/FMUM
|
||||
#define V6X00 HW_VER_REV(0x0,0x0) // FMUV6X, Rev 0
|
||||
#define V6X01 HW_VER_REV(0x0,0x1) // FMUV6X, BMI388 I2C2 Rev 1
|
||||
#define V6X03 HW_VER_REV(0x0,0x3) // FMUV6X, Sensor Set Rev 3
|
||||
#define V6X04 HW_VER_REV(0x0,0x4) // FMUV6X, Sensor Set Rev 4
|
||||
#define V6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
|
||||
#define V6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3
|
||||
#define V6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4
|
||||
#define V6X50 HW_VER_REV(0x5,0x0) // FMUV6X, HB Mini Rev 0
|
||||
#define V6X51 HW_VER_REV(0x5,0x1) // FMUV6X, BMI388 I2C2 HB Mini Rev 1
|
||||
#define V6X53 HW_VER_REV(0x5,0x3) // FMUV6X, Sensor Set HB Mini Rev 3
|
||||
#define V6X54 HW_VER_REV(0x5,0x4) // FMUV6X, Sensor Set HB Mini Rev 4
|
||||
#define V6X00000000 HW_VER_REV(0x0,0x0) // FMUV6X, Rev 0
|
||||
#define V6X00000001 HW_VER_REV(0x0,0x1) // FMUV6X, BMI388 I2C2 Rev 1
|
||||
#define V6X00000003 HW_VER_REV(0x0,0x3) // FMUV6X, Sensor Set Rev 3
|
||||
#define V6X00000004 HW_VER_REV(0x0,0x4) // FMUV6X, Sensor Set Rev 4
|
||||
#define V6X00010000 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0
|
||||
#define V6X00010003 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3
|
||||
#define V6X00010004 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4
|
||||
#define V6X00050000 HW_VER_REV(0x5,0x0) // FMUV6X, HB Mini Rev 0
|
||||
#define V6X00050001 HW_VER_REV(0x5,0x1) // FMUV6X, BMI388 I2C2 HB Mini Rev 1
|
||||
#define V6X00050003 HW_VER_REV(0x5,0x3) // FMUV6X, Sensor Set HB Mini Rev 3
|
||||
#define V6X00050004 HW_VER_REV(0x5,0x4) // FMUV6X, Sensor Set HB Mini Rev 4
|
||||
|
||||
#define UAVCAN_NUM_IFACES_RUNTIME 1
|
||||
|
||||
|
|
|
@ -139,17 +139,17 @@ static const px4_hw_mft_item_t hw_mft_list_v0650[] = {
|
|||
|
||||
static px4_hw_mft_list_entry_t mft_lists[] = {
|
||||
// ver_rev
|
||||
{V6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
|
||||
{V6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2
|
||||
{V6X03, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3
|
||||
{V6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // HB Mini
|
||||
{V6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini
|
||||
{V6X53, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3
|
||||
{V6X54, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4
|
||||
{V6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO
|
||||
{V6X13, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3
|
||||
{V6X04, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4
|
||||
{V6X14, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 4
|
||||
{V6X00000000, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)},
|
||||
{V6X00000001, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2
|
||||
{V6X00000003, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3
|
||||
{V6X00050000, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // HB Mini
|
||||
{V6X00050001, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini
|
||||
{V6X00050003, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3
|
||||
{V6X00050004, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4
|
||||
{V6X00010000, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO
|
||||
{V6X00010003, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3
|
||||
{V6X00000004, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4
|
||||
{V6X00010004, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 4
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -172,7 +172,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
uint32_t ver_rev = board_get_hw_version() << 8;
|
||||
uint32_t ver_rev = board_get_hw_version() << 16;
|
||||
ver_rev |= board_get_hw_revision();
|
||||
|
||||
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
|
||||
|
@ -183,7 +183,7 @@ __EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
|||
}
|
||||
|
||||
if (boards_manifest == px4_hw_mft_list_uninitialized) {
|
||||
syslog(LOG_ERR, "[boot] Board %4" PRIx32 " is not supported!\n", ver_rev);
|
||||
syslog(LOG_ERR, "[boot] Board %08" PRIx32 " is not supported!\n", ver_rev);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -262,7 +262,7 @@
|
|||
|
||||
#if defined(BOARD_HAS_HW_VERSIONING)
|
||||
# define BOARD_HAS_VERSIONING 1
|
||||
# define HW_VER_REV(v,r) ((uint32_t)((v) & 0xff) << 8) | ((uint32_t)(r) & 0xff)
|
||||
# define HW_VER_REV(v,r) ((uint32_t)((v) & 0xffff) << 16) | ((uint32_t)(r) & 0xffff)
|
||||
#endif
|
||||
|
||||
/* Default LED logical to color mapping */
|
||||
|
|
|
@ -52,12 +52,15 @@
|
|||
# define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE
|
||||
# define GPIO_HW_VER_DRIVE GPIO_HW_VER_REV_DRIVE
|
||||
# endif
|
||||
|
||||
#define HW_INFO_SIZE 20 //<! Size to fit hw_info string
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
static int hw_version = 0;
|
||||
static int hw_revision = 0;
|
||||
static char hw_info[] = HW_INFO_INIT;
|
||||
static char hw_info[HW_INFO_SIZE] = {0};
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
|
@ -338,8 +341,16 @@ int board_determine_hw_info()
|
|||
int rv = determine_hw_info(&hw_revision, &hw_version);
|
||||
|
||||
if (rv == OK) {
|
||||
hw_info[HW_INFO_INIT_REV] = board_get_hw_revision() + '0';
|
||||
hw_info[HW_INFO_INIT_VER] = board_get_hw_version() + '0';
|
||||
|
||||
if (rv == OK) {
|
||||
|
||||
int hw_info_size = snprintf(hw_info, HW_INFO_SIZE, HW_INFO_INIT, hw_version, hw_revision);
|
||||
|
||||
if ((hw_info_size < 0) || (hw_info_size >= HW_INFO_SIZE)) {
|
||||
printf("[boot] Error, hw_info string hasn't been completely written\n");
|
||||
rv = -1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
|
|
|
@ -56,12 +56,15 @@
|
|||
# define GPIO_HW_REV_DRIVE GPIO_HW_VER_REV_DRIVE
|
||||
# define GPIO_HW_VER_DRIVE GPIO_HW_VER_REV_DRIVE
|
||||
# endif
|
||||
|
||||
#define HW_INFO_SIZE 20 //<! Size to fit hw_info string
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
static int hw_version = 0;
|
||||
static int hw_revision = 0;
|
||||
static char hw_info[] = HW_INFO_INIT;
|
||||
static char hw_info[HW_INFO_SIZE] = {0};
|
||||
|
||||
static const uint16_t mtd_mft_version = MTD_MFT_v0; //< Current version of structure in EEPROM
|
||||
static const char *mtd_mft_path = "/fs/mtd_mft";
|
||||
|
@ -443,16 +446,31 @@ __EXPORT int board_get_hw_revision()
|
|||
|
||||
int board_determine_hw_info()
|
||||
{
|
||||
// ADC hw version range: {0x1 - 0xF}
|
||||
int rv = determine_hw_info(&hw_revision, &hw_version);
|
||||
|
||||
if (rv == OK) {
|
||||
|
||||
hw_info[HW_INFO_INIT_REV] = board_get_hw_revision() < 10 ?
|
||||
board_get_hw_revision() + '0' :
|
||||
board_get_hw_revision() + 'a' - 10;
|
||||
hw_info[HW_INFO_INIT_VER] = board_get_hw_version() < 10 ?
|
||||
board_get_hw_version() + '0' :
|
||||
board_get_hw_version() + 'a' - 10;
|
||||
/* EEPROM hw version range: {0x10 - 0xFFFF} */
|
||||
if (hw_version == HW_VERSION_EEPROM) {
|
||||
|
||||
mtd_mft_t mtd_mft;
|
||||
rv = board_get_eeprom_hw_info(&mtd_mft);
|
||||
|
||||
if (rv == OK) {
|
||||
hw_version = mtd_mft.hw_extended_ver;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (rv == OK) {
|
||||
|
||||
int hw_info_size = snprintf(hw_info, HW_INFO_SIZE, HW_INFO_INIT, hw_version, hw_revision);
|
||||
|
||||
if ((hw_info_size < 0) || (hw_info_size >= HW_INFO_SIZE)) {
|
||||
printf("[boot] Error, hw_info string hasn't been completely written\n");
|
||||
rv = -1;
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
|
|
Loading…
Reference in New Issue