amiro-blt / Target / Modules / DiWheelDrive_1-2 / Boot / blt_conf.h @ c1f21a71
History | View | Annotate | Download (14.7 KB)
1 |
/************************************************************************************//** |
---|---|
2 |
* \file Demo\ARMCM3_STM32_Olimex_STM32P103_GCC\Boot\blt_conf.h
|
3 |
* \brief Bootloader configuration header file.
|
4 |
* \ingroup Boot_ARMCM3_STM32_Olimex_STM32P103_GCC
|
5 |
* \internal
|
6 |
*----------------------------------------------------------------------------------------
|
7 |
* C O P Y R I G H T
|
8 |
*----------------------------------------------------------------------------------------
|
9 |
* Copyright (c) 2012 by Feaser http://www.feaser.com All rights reserved
|
10 |
*
|
11 |
*----------------------------------------------------------------------------------------
|
12 |
* L I C E N S E
|
13 |
*----------------------------------------------------------------------------------------
|
14 |
* This file is part of OpenBLT. OpenBLT is free software: you can redistribute it and/or
|
15 |
* modify it under the terms of the GNU General Public License as published by the Free
|
16 |
* Software Foundation, either version 3 of the License, or (at your option) any later
|
17 |
* version.
|
18 |
*
|
19 |
* OpenBLT is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
|
20 |
* without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
|
21 |
* PURPOSE. See the GNU General Public License for more details.
|
22 |
*
|
23 |
* You should have received a copy of the GNU General Public License along with OpenBLT.
|
24 |
* If not, see <http://www.gnu.org/licenses/>.
|
25 |
*
|
26 |
* A special exception to the GPL is included to allow you to distribute a combined work
|
27 |
* that includes OpenBLT without being obliged to provide the source code for any
|
28 |
* proprietary components. The exception text is included at the bottom of the license
|
29 |
* file <license.html>.
|
30 |
*
|
31 |
* \endinternal
|
32 |
****************************************************************************************/
|
33 |
#ifndef BLT_CONF_H
|
34 |
#define BLT_CONF_H
|
35 |
|
36 |
/****************************************************************************************
|
37 |
* C P U D R I V E R C O N F I G U R A T I O N
|
38 |
****************************************************************************************/
|
39 |
/* To properly initialize the baudrate clocks of the communication interface, typically
|
40 |
* the speed of the crystal oscillator and/or the speed at which the system runs is
|
41 |
* needed. Set these through configurables BOOT_CPU_XTAL_SPEED_KHZ and
|
42 |
* BOOT_CPU_SYSTEM_SPEED_KHZ, respectively. To enable data exchange with the host that is
|
43 |
* not dependent on the targets architecture, the byte ordering needs to be known.
|
44 |
* Setting BOOT_CPU_BYTE_ORDER_MOTOROLA to 1 selects little endian mode and 0 selects
|
45 |
* big endian mode.
|
46 |
*
|
47 |
* Set BOOT_CPU_USER_PROGRAM_START_HOOK to 1 if you would like a hook function to be
|
48 |
* called the moment the user program is about to be started. This could be used to
|
49 |
* de-initialize application specific parts, for example to stop blinking an LED, etc.
|
50 |
*/
|
51 |
/** \brief Frequency of the external crystal oscillator. */
|
52 |
#define BOOT_CPU_XTAL_SPEED_KHZ (8000) |
53 |
/** \brief Desired system speed. */
|
54 |
#define BOOT_CPU_SYSTEM_SPEED_KHZ (72000) |
55 |
/** \brief Motorola or Intel style byte ordering. */
|
56 |
#define BOOT_CPU_BYTE_ORDER_MOTOROLA (0) |
57 |
/** \brief Enable/disable hook function call right before user program start. */
|
58 |
#define BOOT_CPU_USER_PROGRAM_START_HOOK (1) |
59 |
|
60 |
|
61 |
/****************************************************************************************
|
62 |
* B O O T L O A D E R O F M A I N D E V I C E
|
63 |
****************************************************************************************/
|
64 |
/* It is important to initialize if the bootloader is part of the main device. In this
|
65 |
* case some backdoor loops have to stay opened and backdoor loops of other bootloaders
|
66 |
* have to be controlled by this bootloader. Additionally the bootloader should be able
|
67 |
* to send program code of user programs for other devices.
|
68 |
* Make sure that one of the communication interfaces is the gateway!
|
69 |
*/
|
70 |
/** \brief Bootloader of main device. */
|
71 |
#define BOOTLOADER_OF_MAIN_DEVICE (1) |
72 |
|
73 |
|
74 |
/****************************************************************************************
|
75 |
* C O M M U N I C A T I O N I N T E R F A C E C O N F I G U R A T I O N
|
76 |
****************************************************************************************/
|
77 |
/* The CAN communication interface is selected by setting the BOOT_COM_CAN_ENABLE
|
78 |
* configurable to 1. Configurable BOOT_COM_CAN_BAUDRATE selects the communication speed
|
79 |
* in bits/second. Two CAN messages are reserved for communication with the host. The
|
80 |
* message identifier for sending data from the target to the host is configured with
|
81 |
* BOOT_COM_CAN_TXMSG_ID. The one for receiving data from the host is configured with
|
82 |
* BOOT_COM_CAN_RXMSG_ID. The maximum amount of data bytes in a message for data
|
83 |
* transmission and reception is set through BOOT_COM_CAN_TX_MAX_DATA and
|
84 |
* BOOT_COM_CAN_RX_MAX_DATA, respectively. It is common for a microcontroller to have more
|
85 |
* than 1 CAN controller on board. The zero-based BOOT_COM_CAN_CHANNEL_INDEX selects the
|
86 |
* CAN controller channel.
|
87 |
*
|
88 |
*/
|
89 |
/** \brief Enable/disable CAN transport layer. */
|
90 |
#define BOOT_GATE_CAN_ENABLE (1) |
91 |
/** \brief Configure the desired CAN baudrate. */
|
92 |
#define BOOT_COM_CAN_BAUDRATE (1000000) |
93 |
/** \brief Configure CAN message ID target->host. */
|
94 |
#define BOOT_COM_CAN_TX_MSG_ID (0x700) |
95 |
/** \brief Configure number of bytes in the target->host CAN message. */
|
96 |
#define BOOT_COM_CAN_TX_MAX_DATA (255) |
97 |
/** \brief Configure CAN message ID host->target. */
|
98 |
#define BOOT_COM_CAN_RX_MSG_ID (0x600) |
99 |
/** \brief Configure number of bytes in the host->target CAN message. */
|
100 |
#define BOOT_COM_CAN_RX_MAX_DATA (255) |
101 |
/** \brief Select the desired CAN peripheral as a zero based index. */
|
102 |
#define BOOT_COM_CAN_CHANNEL_INDEX (0) |
103 |
/** \brief Configure CAN message acknowledgement ID addition (ORed with original ID). */
|
104 |
#define BOOT_COM_CAN_MSG_ACK (0x001) |
105 |
/** \brief Configure CAN message ID addition for continuous messages (ORed with original ID). */
|
106 |
#define BOOT_COM_CAN_MSG_SUBSEQUENT (0x002) |
107 |
|
108 |
/**
|
109 |
* \brief Configure device ID for communication (start with 1).
|
110 |
* \details The device ID is a 32 bit integer, which can be interpreted bytewise:
|
111 |
* <AMiRo_revision>:<moduleID>:<moduleVersion_major>:<moduleVersion_minor>
|
112 |
* For this module the according values are
|
113 |
* 1:0:1:2 = 0x01000102
|
114 |
*/
|
115 |
#define BOOT_COM_DEVICE_ID (0x01000102) |
116 |
|
117 |
/* The UART communication interface is selected by setting the BOOT_COM_UART_ENABLE
|
118 |
* configurable to 1. Configurable BOOT_COM_UART_BAUDRATE selects the communication speed
|
119 |
* in bits/second. The maximum amount of data bytes in a message for data transmission
|
120 |
* and reception is set through BOOT_COM_UART_TX_MAX_DATA and BOOT_COM_UART_RX_MAX_DATA,
|
121 |
* respectively. It is common for a microcontroller to have more than 1 UART interface
|
122 |
* on board. The zero-based BOOT_COM_UART_CHANNEL_INDEX selects the UART interface.
|
123 |
*
|
124 |
*/
|
125 |
/** \brief Enable/disable UART transport layer. */
|
126 |
#define BOOT_COM_UART_ENABLE (1) |
127 |
/** \brief Configure the desired communication speed. */
|
128 |
#define BOOT_COM_UART_BAUDRATE (115200) |
129 |
/** \brief Configure number of bytes in the target->host data packet. */
|
130 |
#define BOOT_COM_UART_TX_MAX_DATA (255) |
131 |
/** \brief Configure number of bytes in the host->target data packet. */
|
132 |
#define BOOT_COM_UART_RX_MAX_DATA (255) |
133 |
/** \brief Select the desired UART peripheral as a zero based index. */
|
134 |
#define BOOT_COM_UART_CHANNEL_INDEX (0) |
135 |
/* Activate debugging with UART2 */
|
136 |
#define BOOT_DEBUGGING_UART2_ENABLE (0) |
137 |
|
138 |
|
139 |
/****************************************************************************************
|
140 |
* F I L E S Y S T E M I N T E R F A C E C O N F I G U R A T I O N
|
141 |
****************************************************************************************/
|
142 |
/* The file system interface is selected by setting the BOOT_FILE_SYS_ENABLE configurable
|
143 |
* to 1. This enables support for firmware updates from a file stored on a locally
|
144 |
* attached file system such as an SD-card. Note that this interface can be enabled
|
145 |
* together with one of the remote communication interfaces such as UART, CAN or USB.
|
146 |
*
|
147 |
* Set BOOT_FILE_LOGGING_ENABLE to 1 if you would like log messages to be created during
|
148 |
* a firmware update. The hook function FileFirmwareUpdateLogHook() will be called each
|
149 |
* time a new string formatted log entry is available. This could be used during testing
|
150 |
* by outputting the string on UART or to create a log file on the file system itself.
|
151 |
*
|
152 |
* Set BOOT_FILE_ERROR_HOOK_ENABLE to 1 if you would like to be informed in case an error
|
153 |
* occurs during the firmware update. This could for example be used to turn on an error
|
154 |
* LED to inform the user that something went wrong. Inspecting the log messages provides
|
155 |
* additional information on the error cause.
|
156 |
*
|
157 |
* Set BOOT_FILE_STARTED_HOOK_ENABLE to 1 if you would like to be informed when a new
|
158 |
* firmware update is started by the bootloader.
|
159 |
*
|
160 |
* Set BOOT_FILE_COMPLETED_HOOK_ENABLE to 1 if you would like to be informed when a
|
161 |
* firmware update is completed by the bootloader.
|
162 |
*/
|
163 |
/** \brief Enable/disable support for firmware updates from a locally attached storage.*/
|
164 |
#define BOOT_FILE_SYS_ENABLE (0) |
165 |
/** \brief Enable/disable logging messages during firmware updates. */
|
166 |
#define BOOT_FILE_LOGGING_ENABLE (1) |
167 |
/** \brief Enable/disable a hook function that is called upon detection of an error. */
|
168 |
#define BOOT_FILE_ERROR_HOOK_ENABLE (1) |
169 |
/** \brief Enable/disable a hook function that is called at the start of the update. */
|
170 |
#define BOOT_FILE_STARTED_HOOK_ENABLE (1) |
171 |
/** \brief Enable/disable a hook function that is called at the end of the update. */
|
172 |
#define BOOT_FILE_COMPLETED_HOOK_ENABLE (1) |
173 |
|
174 |
|
175 |
/****************************************************************************************
|
176 |
* B A C K D O O R E N T R Y C O N F I G U R A T I O N
|
177 |
****************************************************************************************/
|
178 |
/* It is possible to implement an application specific method to force the bootloader to
|
179 |
* stay active after a reset. Such a backdoor entry into the bootloader is desired in
|
180 |
* situations where the user program does not run properly and therefore cannot
|
181 |
* reactivate the bootloader. By enabling these hook functions, the application can
|
182 |
* implement the backdoor, which overrides the default backdoor entry that is programmed
|
183 |
* into the bootloader. When desired for security purposes, these hook functions can
|
184 |
* also be implemented in a way that disables the backdoor entry altogether.
|
185 |
*/
|
186 |
/** \brief Enable/disable the backdoor override hook functions. */
|
187 |
#define BOOT_BACKDOOR_HOOKS_ENABLE (1) |
188 |
|
189 |
|
190 |
/****************************************************************************************
|
191 |
* N O N - V O L A T I L E M E M O R Y D R I V E R C O N F I G U R A T I O N
|
192 |
****************************************************************************************/
|
193 |
/* The NVM driver typically supports erase and program operations of the internal memory
|
194 |
* present on the microcontroller. Through these hook functions the NVM driver can be
|
195 |
* extended to support additional memory types such as external flash memory and serial
|
196 |
* eeproms. The size of the internal memory in kilobytes is specified with configurable
|
197 |
* BOOT_NVM_SIZE_KB. If desired the internal checksum writing and verification method can
|
198 |
* be overridden with a application specific method by enabling configuration switch
|
199 |
* BOOT_NVM_CHECKSUM_HOOKS_ENABLE.
|
200 |
*/
|
201 |
/** \brief Enable/disable the NVM hook function for supporting additional memory devices. */
|
202 |
#define BOOT_NVM_HOOKS_ENABLE (0) |
203 |
/** \brief Configure the size of the default memory device (typically flash EEPROM). */
|
204 |
#define BOOT_NVM_SIZE_KB (512) |
205 |
/** \brief Enable/disable hooks functions to override the user program checksum handling. */
|
206 |
#define BOOT_NVM_CHECKSUM_HOOKS_ENABLE (0) |
207 |
|
208 |
|
209 |
/****************************************************************************************
|
210 |
* W A T C H D O G D R I V E R C O N F I G U R A T I O N
|
211 |
****************************************************************************************/
|
212 |
/* The COP driver cannot be configured internally in the bootloader, because its use
|
213 |
* and configuration is application specific. The bootloader does need to service the
|
214 |
* watchdog in case it is used. When the application requires the use of a watchdog,
|
215 |
* set BOOT_COP_HOOKS_ENABLE to be able to initialize and service the watchdog through
|
216 |
* hook functions.
|
217 |
*/
|
218 |
/** \brief Enable/disable the hook functions for controlling the watchdog. */
|
219 |
#define BOOT_COP_HOOKS_ENABLE (0) |
220 |
|
221 |
|
222 |
/****************************************************************************************
|
223 |
* S E E D / K E Y S E C U R I T Y C O N F I G U R A T I O N
|
224 |
****************************************************************************************/
|
225 |
/* A security mechanism can be enabled in the bootloader's XCP module by setting configu-
|
226 |
* rable BOOT_XCP_SEED_KEY_ENABLE to 1. Before any memory erase or programming
|
227 |
* operations can be performed, access to this resource need to be unlocked.
|
228 |
* In the Microboot settings on tab "XCP Protection" you need to specify a DLL that
|
229 |
* implements the unlocking algorithm. The demo programs are configured for the (simple)
|
230 |
* algorithm in "FeaserKey.dll". The source code for this DLL is available so it can be
|
231 |
* customized to your needs.
|
232 |
* During the unlock sequence, Microboot requests a seed from the bootloader, which is in
|
233 |
* the format of a byte array. Using this seed the unlock algorithm in the DLL computes
|
234 |
* a key, which is also a byte array, and sends this back to the bootloader. The
|
235 |
* bootloader then verifies this key to determine if programming and erase operations are
|
236 |
* permitted.
|
237 |
* After enabling this feature the hook functions XcpGetSeedHook() and XcpVerifyKeyHook()
|
238 |
* are called by the bootloader to obtain the seed and to verify the key, respectively.
|
239 |
*/
|
240 |
#define BOOT_XCP_SEED_KEY_ENABLE (0) |
241 |
|
242 |
|
243 |
|
244 |
/****************************************************************************************
|
245 |
* F L A S H I N G M O D E T I M E O U T
|
246 |
****************************************************************************************/
|
247 |
/* Sets the timeout for being in flashing mode. The bootloader stays in flashing mode
|
248 |
* after a connection has been closed. The timer will be reset with every new connection.
|
249 |
*/
|
250 |
#define FLASHING_WITHOUT_CONNECTION_TIMEOUT_MS 30000 // 30 seconds |
251 |
|
252 |
|
253 |
#endif /* BLT_CONF_H */ |
254 |
/*********************************** end of blt_conf.h *********************************/
|