board_hw_info: add set and get functions for hw_version to/from eeprom

This commit is contained in:
Igor Mišić 2021-12-20 14:51:21 +01:00 committed by Beat Küng
parent dd38ced7c4
commit b938215c2b
3 changed files with 251 additions and 1 deletions

View File

@ -0,0 +1,105 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#define HW_VERSION_EEPROM 0x7 //!< Get hw_info from EEPROM
#define HW_EEPROM_VERSION_MIN 0x10 //!< Minimum supported version
#pragma pack(push, 1)
typedef struct {
uint16_t format_version;
uint16_t hw_extended_ver;
uint16_t crc;
} mtd_mft_v0_t;
typedef struct {
uint16_t format_version;
uint16_t hw_extended_ver;
//{device tree overlay}
uint16_t crc;
} mtd_mft_v1_t;
typedef struct {
uint16_t hw_extended_ver;
//{device tree overlay}
} mtd_mft_t;
#pragma pack(pop)
#define MTD_MFT_v0 0U //<! EEPROM MTD MFT structure version 0
#define MTD_MFT_v1 1U //<! EEPROM MTD MFT structure version 1
#define MTD_MFT_OFFSET 0 //<! Offset in EEPROM where mtd_mft data starts
/************************************************************************************
* Name: board_set_eeprom_hw_info
*
* Description:
* Function for writing hardware info to EEPROM
*
* Input Parameters:
* *mtd_mft - pointer to mtd_mft to write hw_info
*
* Returned Value:
* 0 - Successful storing to EEPROM
* -1 - Error while storing to EEPROM
*
************************************************************************************/
#if !defined(BOARD_HAS_SIMPLE_HW_VERSIONING) && defined(BOARD_HAS_VERSIONING)
__EXPORT int board_set_eeprom_hw_info(mtd_mft_t *mtd_mft);
#else
static inline int board_set_eeprom_hw_info(mtd_mft_t *mtd_mft) { return -ENOSYS; }
#endif
/************************************************************************************
* Name: board_get_eeprom_hw_info
*
* Description:
* Function for reading hardware info from EEPROM
*
* Output Parameters:
* *mtd_mft - pointer to mtd_mft to read hw_info
*
* Returned Value:
* 0 - Successful reading from EEPROM
* -1 - Error while reading from EEPROM
*
************************************************************************************/
#if !defined(BOARD_HAS_SIMPLE_HW_VERSIONING) && defined(BOARD_HAS_VERSIONING)
__EXPORT int board_get_eeprom_hw_info(mtd_mft_t *mtd_mft);
#else
static inline int board_get_eeprom_hw_info(mtd_mft_t *mtd_mft) { return -ENOSYS; }
#endif

View File

@ -34,4 +34,4 @@
px4_add_library(arch_board_hw_info
board_hw_rev_ver.c
)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc systemlib)

View File

@ -42,9 +42,12 @@
#include <px4_platform_common/micro_hal.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_hw_eeprom_rev_ver.h>
#include <stdio.h>
#include <fcntl.h>
#include <board_config.h>
#include <systemlib/crc.h>
#include <systemlib/px4_macros.h>
#if defined(BOARD_HAS_HW_VERSIONING)
@ -60,6 +63,9 @@ static int hw_version = 0;
static int hw_revision = 0;
static char hw_info[] = HW_INFO_INIT;
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";
/****************************************************************************
* Protected Functions
****************************************************************************/
@ -451,4 +457,143 @@ int board_determine_hw_info()
return rv;
}
/************************************************************************************
* Name: board_set_eeprom_hw_info
*
* Description:
* Function for writing hardware info to EEPROM
*
* Input Parameters:
* *mtd_mft - pointer to mtd_mft to write hw_info
*
* Returned Value:
* 0 - Successful storing to EEPROM
* -1 - Error while storing to EEPROM
*
************************************************************************************/
__EXPORT int board_set_eeprom_hw_info(mtd_mft_t *mtd_mft)
{
if (mtd_mft == NULL) {
return -1;
}
if (mtd_mft->hw_extended_ver < HW_EEPROM_VERSION_MIN) {
printf("hardware version for EEPROM must be greater than %x\n", HW_EEPROM_VERSION_MIN);
return -EINVAL;
}
int fd = open(mtd_mft_path, O_WRONLY);
if (fd < 0) {
return -errno;
}
int ret_val = OK;
mtd_mft_v0_t mtd_mft_v0 = {
.format_version = mtd_mft_version,
.hw_extended_ver = mtd_mft->hw_extended_ver
};
mtd_mft_v0.crc = crc16_signature(CRC16_INITIAL, sizeof(mtd_mft_v0) - sizeof(mtd_mft_v0.crc), (uint8_t *)&mtd_mft_v0);
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(sizeof(mtd_mft_v0) != write(fd, &mtd_mft_v0, sizeof(mtd_mft_v0)))
) {
ret_val = -errno;
}
if (fd >= 0) {
close(fd);
fd = -1;
}
return ret_val;
}
/************************************************************************************
* Name: board_get_eeprom_hw_info
*
* Description:
* Function for reading hardware info from EEPROM
*
* Output Parameters:
* *mtd_mft - pointer to mtd_mft to read hw_info
*
* Returned Value:
* 0 - Successful reading from EEPROM
* -1 - Error while reading from EEPROM
*
************************************************************************************/
__EXPORT int board_get_eeprom_hw_info(mtd_mft_t *mtd_mft)
{
int fd = open(mtd_mft_path, O_RDONLY);
if ((fd < 0) || (mtd_mft == NULL)) {
return -errno;
}
int ret_val = OK;
uint16_t format_version = 0;
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(sizeof(format_version) != read(fd, &format_version, sizeof(format_version)))
) {
ret_val = -errno;
} else {
uint16_t buffer_size = 0;
if (MTD_MFT_v0 == format_version) {
buffer_size = sizeof(mtd_mft_v0_t);
} else if (MTD_MFT_v1 == format_version) {
buffer_size = sizeof(mtd_mft_v1_t);
} else {
printf("[boot] Error, unknown version %d of mtd_mft in EEPROM\n", format_version);
ret_val = -1;
}
if (ret_val == OK) {
uint8_t buffer[buffer_size];
memset(buffer, 0u, buffer_size);
if (
(MTD_MFT_OFFSET != lseek(fd, MTD_MFT_OFFSET, SEEK_SET)) ||
(buffer_size != read(fd, buffer, buffer_size))
) {
ret_val = -errno;
} else {
uint16_t crc = 0, eeprom_crc = 0;
crc = crc16_signature(CRC16_INITIAL, buffer_size - sizeof(crc), buffer);
eeprom_crc = (uint16_t)((buffer[buffer_size - 1] << 8) | buffer[buffer_size - 2]);
if (crc == eeprom_crc) {
memcpy(mtd_mft, &buffer[sizeof(format_version)], buffer_size - sizeof(format_version) - sizeof(crc));
} else {
ret_val = -1;
}
}
}
}
if (fd >= 0) {
close(fd);
fd = -1;
}
return ret_val;
}
#endif