Browse Source

boot_app_shared automatically generate UAVCAN bootable image

release/1.12
Daniel Agar 4 years ago committed by David Sidrane
parent
commit
b422da45ec
  1. 11
      boards/cuav/can-gps-v1/default.cmake
  2. 11
      boards/px4/fmu-v4/cannode.cmake
  3. 99
      cmake/px4_make_uavcan_bootloader.cmake
  4. 34
      src/drivers/bootloaders/CMakeLists.txt
  5. 17
      src/drivers/bootloaders/make_can_boot_descriptor.py

11
boards/cuav/can-gps-v1/default.cmake

@ -51,14 +51,3 @@ px4_add_board(
ver ver
work_queue work_queue
) )
include(px4_make_uavcan_bootloader)
px4_make_uavcan_bootloadable(
BOARD ${PX4_BOARD}
BIN ${PX4_BINARY_DIR}/${PX4_BOARD}.bin
HWNAME ${uavcanblid_name}
HW_MAJOR ${uavcanblid_hw_version_major}
HW_MINOR ${uavcanblid_hw_version_minor}
SW_MAJOR ${uavcanblid_sw_version_major}
SW_MINOR ${uavcanblid_sw_version_minor}
)

11
boards/px4/fmu-v4/cannode.cmake

@ -88,14 +88,3 @@ px4_add_board(
ver ver
work_queue work_queue
) )
include(px4_make_uavcan_bootloader)
px4_make_uavcan_bootloadable(
BOARD ${PX4_BOARD}
BIN ${PX4_BINARY_DIR}/${PX4_BOARD}.bin
HWNAME ${uavcanblid_name}
HW_MAJOR ${uavcanblid_hw_version_major}
HW_MINOR ${uavcanblid_hw_version_minor}
SW_MAJOR ${uavcanblid_sw_version_major}
SW_MINOR ${uavcanblid_sw_version_minor}
)

99
cmake/px4_make_uavcan_bootloader.cmake

@ -1,99 +0,0 @@
############################################################################
#
# Copyright (c) 2015 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.
#
############################################################################
#=============================================================================
#
# px4_make_uavcan_bootloadable
#
# This function adds a uavcan boot loadable target.
#
# Usage:
# px4_make_uavcan_bootloadable(
# BOARD <board>
# BIN <input bin file>)
# HWNAME <uavcan name>
# HW_MAJOR <number>
# HW_MINOR <number>
# SW_MAJOR <number>
# SW_MINOR <number>)
#
# Input:
# BOARD : the board
# BIN : the bin file to generate the bootloadable image from
# HWNAME : the uavcan name
# HW_MAJOR : the major hardware revision
# HW_MINOR : the minor hardware revision
# SW_MAJOR : the major software revision
# SW_MINOR : the minor software revision
#
# Output:
# OUT : None
#
# Example:
# px4_make_uavcan_bootloadable(
# BOARD ${PX4_BOARD}
# BIN ${CMAKE_CURRENT_BINARY_DIR}/firmware_nuttx
# HWNAME ${uavcanblid_name}
# HW_MAJOR ${uavcanblid_hw_version_major}
# HW_MINOR ${uavcanblid_hw_version_minor}
# SW_MAJOR ${uavcanblid_sw_version_major}
# SW_MINOR ${uavcanblid_sw_version_minor}
# )
#
function(px4_make_uavcan_bootloadable)
px4_parse_function_args(
NAME px4_make_uavcan_bootloadable
ONE_VALUE BOARD BIN HWNAME HW_MAJOR HW_MINOR SW_MAJOR SW_MINOR
REQUIRED BOARD BIN HWNAME HW_MAJOR HW_MINOR SW_MAJOR SW_MINOR
ARGN ${ARGN})
string(REPLACE "\"" "" HWNAME ${HWNAME})
execute_process(
COMMAND git rev-list HEAD --max-count=1 --abbrev=8 --abbrev-commit
OUTPUT_VARIABLE uavcanbl_git_desc
OUTPUT_STRIP_TRAILING_WHITESPACE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
if ("${uavcanbl_git_desc}" STREQUAL "")
set(uavcanbl_git_desc ffffffff)
endif()
set(uavcan_bl_imange_name ${HWNAME}-${HW_MAJOR}.${HW_MINOR}-${SW_MAJOR}.${SW_MINOR}.${uavcanbl_git_desc}.uavcan.bin)
message(STATUS "Generating UAVCAN Bootable as ${uavcan_bl_imange_name}")
add_custom_command(OUTPUT ${uavcan_bl_imange_name}
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/make_can_boot_descriptor.py
-v --use-git-hash ${BIN} ${uavcan_bl_imange_name}
DEPENDS ${BIN})
add_custom_target(build_uavcan_bl_${PX4_BOARD} ALL DEPENDS ${uavcan_bl_imange_name})
endfunction()

34
src/drivers/bootloaders/CMakeLists.txt

@ -37,3 +37,37 @@ add_dependencies(drivers_bootloaders prebuild_targets)
include_directories(include) include_directories(include)
target_include_directories(drivers_bootloaders INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}) target_include_directories(drivers_bootloaders INTERFACE ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(drivers_bootloaders PRIVATE systemlib) target_link_libraries(drivers_bootloaders PRIVATE systemlib)
# generate bootloader_app_shared_t
if(NOT "${PX4_BOARD_LABEL}" MATCHES "canbootloader")
set(HW_MAJOR ${uavcanblid_hw_version_major})
set(HW_MINOR ${uavcanblid_hw_version_minor})
set(SW_MAJOR ${uavcanblid_sw_version_major})
set(SW_MINOR ${uavcanblid_sw_version_minor})
string(REPLACE "\"" "" HWNAME ${uavcanblid_name})
execute_process(
COMMAND git rev-list HEAD --max-count=1 --abbrev=8 --abbrev-commit
OUTPUT_VARIABLE uavcanbl_git_desc
OUTPUT_STRIP_TRAILING_WHITESPACE
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
)
if ("${uavcanbl_git_desc}" STREQUAL "")
set(uavcanbl_git_desc ffffffff)
endif()
set(uavcan_bl_imange_name ${HWNAME}-${HW_MAJOR}.${HW_MINOR}-${SW_MAJOR}.${SW_MINOR}.${uavcanbl_git_desc}.uavcan.bin)
message(STATUS "Generating UAVCAN Bootable as ${uavcan_bl_imange_name}")
add_custom_command(OUTPUT ${uavcan_bl_imange_name}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/make_can_boot_descriptor.py
-v --use-git-hash ${PX4_BINARY_DIR}/${PX4_BOARD}.bin ${uavcan_bl_imange_name}
DEPENDS
${PX4_BINARY_DIR}/${PX4_BOARD}.bin
${CMAKE_CURRENT_SOURCE_DIR}/make_can_boot_descriptor.py
WORKING_DIRECTORY
${PX4_BINARY_DIR}
)
add_custom_target(build_uavcan_bl ALL DEPENDS ${uavcan_bl_imange_name})
endif()

17
Tools/make_can_boot_descriptor.py → src/drivers/bootloaders/make_can_boot_descriptor.py

@ -305,21 +305,7 @@ bootloader image to the output image.
""".format(in_image, in_image.app_descriptor, out_image.app_descriptor, """.format(in_image, in_image.app_descriptor, out_image.app_descriptor,
bootloader_size, len(bootloader_image))) bootloader_size, len(bootloader_image)))
sys.stderr.write( sys.stderr.write(
"""READ VALUES """------------------------------------------------------------------------------
------------------------------------------------------------------------------
Field Type Value
signature uint64 {1.signature!r}
image_crc uint64 0x{1.image_crc:016X}
image_size uint32 0x{1.image_size:X} ({1.image_size:d} B)
vcs_commit uint32 {1.vcs_commit:08X}
version_major uint8 {1.version_major:d}
version_minor uint8 {1.version_minor:d}
reserved uint8[6] {1.reserved!r}
WRITTEN VALUES
------------------------------------------------------------------------------
Field Type Value Field Type Value
signature uint64 {2.signature!r} signature uint64 {2.signature!r}
image_crc uint64 0x{2.image_crc:016X} image_crc uint64 0x{2.image_crc:016X}
@ -328,7 +314,6 @@ vcs_commit uint32 {2.vcs_commit:08X}
version_major uint8 {2.version_major:d} version_major uint8 {2.version_major:d}
version_minor uint8 {2.version_minor:d} version_minor uint8 {2.version_minor:d}
reserved uint8[6] {2.reserved!r} reserved uint8[6] {2.reserved!r}
""".format(in_image, in_image.app_descriptor, out_image.app_descriptor, """.format(in_image, in_image.app_descriptor, out_image.app_descriptor,
bootloader_size, len(bootloader_image))) bootloader_size, len(bootloader_image)))
if out_image.padding: if out_image.padding:
Loading…
Cancel
Save