Browse Source

Adds a board common API for retriving the SoC' Silicon revision data/errata

This abstraction will support mcu's other than the stm32 family.
    It moves the systemlib/mcu_version.c functionality to
    common/stm32/board_mcu_version.c
sbg
David Sidrane 8 years ago committed by Lorenz Meier
parent
commit
242f563d44
  1. 21
      src/drivers/boards/common/board_common.h
  2. 46
      src/drivers/boards/common/stm32/board_mcu_version.c
  3. 1
      src/modules/systemlib/CMakeLists.txt
  4. 58
      src/modules/systemlib/mcu_version.h

21
src/drivers/boards/common/board_common.h

@ -375,3 +375,24 @@ __EXPORT int board_get_uuid_formated32(char *format_buffer, int size, @@ -375,3 +375,24 @@ __EXPORT int board_get_uuid_formated32(char *format_buffer, int size,
const char *seperator,
raw_uuid_uint32_reorder_t *optional_reorder);
#endif // !defined(BOARD_OVERRIDE_UUID)
/************************************************************************************
* Name: board_mcu_version
*
* Description:
* All boards either provide a way to retrieve the cpu revision
* Or define BOARD_OVERRIDE_CPU_VERSION
*
* rev - The silicon revision character
* revstr - The full chip name string
* errata -The eratta if any.
*
* return - The silicon revision / version number as integer
* or -1 on error and rev, revstr and errata will
* not be set
*/
#if defined(BOARD_OVERRIDE_CPU_VERSION)
#define board_mcu_version(rev, revstr, errata) BOARD_OVERRIDE_CPU_VERSION
#else
__EXPORT int board_mcu_version(char *rev, const char **revstr, const char **errata);
#endif // !defined(BOARD_OVERRIDE_CPU_VERSION)

46
src/modules/systemlib/mcu_version.c → src/drivers/boards/common/stm32/board_mcu_version.c

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
/****************************************************************************
*
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -32,26 +33,33 @@ @@ -32,26 +33,33 @@
****************************************************************************/
/**
* @file mcu_version.c
*
* Read out the microcontroller version from the board
*
* @author Lorenz Meier <lorenz@px4.io>
*
* @file board_mcu_version.c
* Implementation of STM32 based SoC version API
*/
#include "mcu_version.h"
#include <px4_config.h>
#include <px4_defines.h>
#if defined(CONFIG_ARCH_CHIP_STM32) || defined(CONFIG_ARCH_CHIP_STM32F7)
/* magic numbers from reference manual */
enum MCU_REV {
MCU_REV_STM32F4_REV_A = 0x1000,
MCU_REV_STM32F4_REV_Z = 0x1001,
MCU_REV_STM32F4_REV_Y = 0x1003,
MCU_REV_STM32F4_REV_1 = 0x1007,
MCU_REV_STM32F4_REV_3 = 0x2001
};
/* Define any issues with the Silicon as lines separated by \n
* omitting the last \n
*/
#define STM32_F4_ERRATA "This device can only utilize a maximum of 1MB flash safely!"
//STM DocID018909 Rev 8 Sect 38.18 and DocID026670 Rev 5 40.6.1 (MCU device ID code)
# define REVID_MASK 0xFFFF0000
# define DEVID_MASK 0xFFF
# define STM32F74xxx_75xxx 0x449
# define STM32F76xxx_77xxx 0x451
# define STM32F40x_41x 0x413
@ -62,16 +70,14 @@ @@ -62,16 +70,14 @@
# define STM32F103_XLD 0x430
# define STM32F103_CON 0x418
#endif
int mcu_version(char *rev, char **revstr)
int board_mcu_version(char *rev, const char **revstr, const char **errata)
{
#ifdef __PX4_NUTTX
uint32_t abc = getreg32(STM32_DEBUGMCU_BASE);
int32_t chip_version = abc & DEVID_MASK;
enum MCU_REV revid = (abc & REVID_MASK) >> 16;
const char *chip_errata = NULL;
switch (chip_version) {
@ -85,6 +91,8 @@ int mcu_version(char *rev, char **revstr) @@ -85,6 +91,8 @@ int mcu_version(char *rev, char **revstr)
case STM32F42x_43x:
*revstr = "STM32F42x";
/* Set possible errata */
chip_errata = STM32_F4_ERRATA;
break;
case STM32F103_LD:
@ -132,6 +140,7 @@ int mcu_version(char *rev, char **revstr) @@ -132,6 +140,7 @@ int mcu_version(char *rev, char **revstr)
case MCU_REV_STM32F4_REV_3:
*rev = '3';
chip_errata = NULL;
break;
default:
@ -141,8 +150,9 @@ int mcu_version(char *rev, char **revstr) @@ -141,8 +150,9 @@ int mcu_version(char *rev, char **revstr)
break;
}
if (errata) {
*errata = chip_errata;
}
return revid;
#else
return -1;
#endif
}

1
src/modules/systemlib/CMakeLists.txt

@ -45,7 +45,6 @@ set(SRCS @@ -45,7 +45,6 @@ set(SRCS
otp.c
board_serial.c
pwm_limit/pwm_limit.c
mcu_version.c
bson/tinybson.c
circuit_breaker.cpp
battery.cpp

58
src/modules/systemlib/mcu_version.h

@ -1,58 +0,0 @@ @@ -1,58 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2014 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
#include <stdint.h>
__BEGIN_DECLS
/* magic numbers from reference manual */
enum MCU_REV {
MCU_REV_STM32F4_REV_A = 0x1000,
MCU_REV_STM32F4_REV_Z = 0x1001,
MCU_REV_STM32F4_REV_Y = 0x1003,
MCU_REV_STM32F4_REV_1 = 0x1007,
MCU_REV_STM32F4_REV_3 = 0x2001
};
/**
* Reports the microcontroller version of the main CPU.
*
* @param rev The silicon revision character
* @param revstr The full chip name string
* @return The silicon revision / version number as integer. -1 on error (rev and revstr will not be set)
*/
__EXPORT int mcu_version(char *rev, char **revstr);
__END_DECLS
Loading…
Cancel
Save