PX4 Firmware
PX4 Autopilot Software http://px4.io
boot_app_shared.c File Reference
#include <nuttx/config.h>
#include <stdint.h>
#include <string.h>
#include "chip.h"
#include "stm32.h"
#include <errno.h>
#include "boot_app_shared.h"
#include "systemlib/crc.h"
Include dependency graph for boot_app_shared.c:

Go to the source code of this file.

Macros

#define BOOTLOADER_COMMON_APP_SIGNATURE   0xB0A04150u
 
#define BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE   0xB0A0424Cu
 
#define crc_HiLOC   STM32_CAN1_FIR(2,1)
 
#define crc_LoLOC   STM32_CAN1_FIR(2,2)
 
#define signature_LOC   STM32_CAN1_FIR(3,1)
 
#define bus_speed_LOC   STM32_CAN1_FIR(3,2)
 
#define node_id_LOC   STM32_CAN1_FIR(4,1)
 
#define CRC_H   1
 
#define CRC_L   0
 

Functions

static void read (bootloader_app_shared_t *pshared)
 
static void write (bootloader_app_shared_t *pshared)
 
static uint64_t calulate_signature (bootloader_app_shared_t *pshared)
 
static void bootloader_app_shared_init (bootloader_app_shared_t *pshared, eRole_t role)
 
__EXPORT int bootloader_app_shared_read (bootloader_app_shared_t *shared, eRole_t role)
 
__EXPORT void bootloader_app_shared_write (bootloader_app_shared_t *shared, eRole_t role)
 
__EXPORT void bootloader_app_shared_invalidate (void)
 

Macro Definition Documentation

◆ BOOTLOADER_COMMON_APP_SIGNATURE

#define BOOTLOADER_COMMON_APP_SIGNATURE   0xB0A04150u

◆ BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE

#define BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE   0xB0A0424Cu

◆ bus_speed_LOC

#define bus_speed_LOC   STM32_CAN1_FIR(3,2)

Definition at line 71 of file boot_app_shared.c.

Referenced by read(), and write().

◆ CRC_H

#define CRC_H   1

Definition at line 73 of file boot_app_shared.c.

Referenced by read(), and write().

◆ crc_HiLOC

#define crc_HiLOC   STM32_CAN1_FIR(2,1)

Definition at line 68 of file boot_app_shared.c.

Referenced by read(), and write().

◆ CRC_L

#define CRC_L   0

Definition at line 74 of file boot_app_shared.c.

Referenced by read(), and write().

◆ crc_LoLOC

#define crc_LoLOC   STM32_CAN1_FIR(2,2)

Definition at line 69 of file boot_app_shared.c.

Referenced by read(), and write().

◆ node_id_LOC

#define node_id_LOC   STM32_CAN1_FIR(4,1)

Definition at line 72 of file boot_app_shared.c.

Referenced by read(), and write().

◆ signature_LOC

#define signature_LOC   STM32_CAN1_FIR(3,1)

Definition at line 70 of file boot_app_shared.c.

Referenced by read(), and write().

Function Documentation

◆ bootloader_app_shared_init()

static void bootloader_app_shared_init ( bootloader_app_shared_t pshared,
eRole_t  role 
)
static

Definition at line 141 of file boot_app_shared.c.

References App, BOOTLOADER_COMMON_APP_SIGNATURE, BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE, Invalid, and bootloader_app_shared_t::signature.

Referenced by bootloader_app_shared_invalidate().

Here is the caller graph for this function:

◆ bootloader_app_shared_invalidate()

__EXPORT void bootloader_app_shared_invalidate ( void  )

Definition at line 260 of file boot_app_shared.c.

References bootloader_app_shared_init(), Invalid, and write().

Referenced by uavcannode_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ bootloader_app_shared_read()

__EXPORT int bootloader_app_shared_read ( bootloader_app_shared_t shared,
eRole_t  role 
)

Definition at line 186 of file boot_app_shared.c.

References App, BOOTLOADER_COMMON_APP_SIGNATURE, BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE, calulate_signature(), bootloader_app_shared_t::crc, OK, read(), bootloader_app_shared_t::signature, and bootloader_app_shared_t::ull.

Referenced by uavcannode_start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ bootloader_app_shared_write()

__EXPORT void bootloader_app_shared_write ( bootloader_app_shared_t shared,
eRole_t  role 
)

Definition at line 228 of file boot_app_shared.c.

References App, BOOTLOADER_COMMON_APP_SIGNATURE, BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE, calulate_signature(), bootloader_app_shared_t::crc, bootloader_app_shared_t::signature, bootloader_app_shared_t::ull, and write().

Referenced by UavcanEsc::cb_beginfirmware_update(), and UavcanNode::cb_beginfirmware_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calulate_signature()

static uint64_t calulate_signature ( bootloader_app_shared_t pshared)
static

Definition at line 128 of file boot_app_shared.c.

References bootloader_app_shared_t::bus_speed, crc64_add_word(), CRC64_INITIAL, CRC64_OUTPUT_XOR, bootloader_app_shared_t::node_id, and bootloader_app_shared_t::signature.

Referenced by bootloader_app_shared_read(), and bootloader_app_shared_write().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read()

static void read ( bootloader_app_shared_t pshared)
inlinestatic

Definition at line 100 of file boot_app_shared.c.

References bootloader_app_shared_t::bus_speed, bus_speed_LOC, bootloader_app_shared_t::crc, CRC_H, crc_HiLOC, CRC_L, crc_LoLOC, bootloader_app_shared_t::node_id, node_id_LOC, bootloader_app_shared_t::signature, signature_LOC, and bootloader_app_shared_t::ul.

Referenced by MavlinkFtpTest::_burst_test(), MavlinkFTP::_copy_file(), linux_sbus::RcInput::_measure(), MavlinkFtpTest::_read_test(), RoboClaw::_transaction(), MavlinkFTP::_workCalcFileCRC32(), MavlinkFTP::_workRead(), bl_update_main(), bootloader_app_shared_read(), calc_timer_diff_to_dsp_us(), CDevNode::CDevNode(), check_user_abort(), LidarLitePWM::collect(), TFMINI::collect(), CM8JL65::collect(), PGA460::collect_results(), UavcanServers::copyFw(), RCInput::cycle(), dsm_input(), esc_calib_main(), frsky_telemetry_thread_main(), PGA460::get_temperature(), hardfault_append_to_ulog(), hardfault_dowrite(), hardfault_increment_reboot(), uart_esc::initialize_mixer(), snapdragon_pwm::initialize_mixer(), listener(), mtd_main(), Simulator::poll_for_MAVLink_messages(), GPS::pollOrRead(), pwm_main(), PX4IO_serial_interface(), MavlinkShell::read(), ReadBuffer::read(), linux_pwm_out::PCA9685::read_byte(), tap_esc_common::read_data_from_uart(), PGA460::read_eeprom(), PGA460::read_register(), read_stack(), PGA460::read_threshold_registers(), read_with_retry(), LinuxGPIO::readValue(), receive_loop(), PX4IO_Uploader::recv_byte_with_timeout(), recv_data(), recv_req_id(), reflect_main(), MavlinkReceiver::Run(), sbus_input(), MavlinkFTP::send(), send_data(), send_poll(), uORB::DeviceMaster::showTop(), spektrum_rc::task_main(), pmw3901::test(), bmm150::test(), rm3100::test(), lis3mdl::test(), test_corruption(), test_file(), test_hott_telemetry(), test_jig_voltages(), test_mount(), test_servo(), test_uart_loopback(), top_main(), and DShotTelemetry::update().

◆ write()

static void write ( bootloader_app_shared_t pshared)
inlinestatic

Definition at line 114 of file boot_app_shared.c.

References bootloader_app_shared_t::bus_speed, bus_speed_LOC, bootloader_app_shared_t::crc, CRC_H, crc_HiLOC, CRC_L, crc_LoLOC, bootloader_app_shared_t::node_id, node_id_LOC, bootloader_app_shared_t::signature, signature_LOC, and bootloader_app_shared_t::ul.

Referenced by MavlinkFTP::_copy_file(), RoboClaw::_transaction(), MavlinkFTP::_workTruncateFile(), MavlinkFTP::_workWrite(), bootloader_app_shared_invalidate(), bootloader_app_shared_write(), GPS::callback(), CDevNode::CDevNode(), UavcanServers::copyFw(), crsf_send_telemetry_attitude(), crsf_send_telemetry_battery(), crsf_send_telemetry_flight_mode(), crsf_send_telemetry_gps(), dumpfile_main(), LinuxGPIO::exportPin(), PGA460::flash_eeprom(), frsky_send_byte(), frsky_send_startstop(), PGA460::get_temperature(), hardfault_append_to_ulog(), hardfault_increment_reboot(), PGA460::initialize_thresholds(), GPS::injectData(), mtd_main(), linux_pwm_out::NavioSysfsPWMOut::pwm_write_sysfs(), PX4IO_serial_interface(), linux_pwm_out::PCA9685::read_byte(), PGA460::read_eeprom(), PGA460::read_register(), PGA460::read_threshold_registers(), reflect_main(), PGA460::request_results(), sbus1_output(), PX4IO_Uploader::send(), Mavlink::send_bytes(), send_data(), linux_pwm_out::NavioSysfsPWMOut::send_output_pwm(), tap_esc_common::send_packet(), send_poll(), LinuxGPIO::setDirection(), sPort_send_byte(), sPort_send_data(), PGA460::take_measurement(), test_corruption(), test_file(), test_hott_telemetry(), test_mount(), test_uart_baudchange(), test_uart_break(), test_uart_console(), test_uart_loopback(), test_uart_send(), px4::logger::LogWriterFile::thread_id(), LinuxGPIO::unexportPin(), PGA460::unlock_eeprom(), MavlinkShell::write(), linux_pwm_out::PCA9685::write_byte(), write_dump_info(), write_dump_time(), PGA460::write_eeprom(), PGA460::write_register(), write_registers(), write_registers_info(), write_stack(), write_stack_detail(), write_test(), and LinuxGPIO::writeValue().