Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
#include "modules/px4_flash/px4_flash.h"
#include "modules/px4_flash/protocol.h"
#include "mcu_periph/sys_time_arch.h"
#include "modules/intermcu/intermcu_ap.h"
#include "mcu_periph/uart.h"
#include "mcu_periph/usb_serial.h"
#include "mcu.h"
#include "led.h"
#include "mcu_arch.h"
#include "mcu_periph/sys_time.h"
Go to the source code of this file.
Macros | |
#define | FLASH_PORT (&((FLASH_UART).device)) |
#define | PX4_IO_FORCE_PROG FALSE |
#define | PROTO_INSYNC 0x12 |
'in sync' byte sent before status More... | |
#define | PROTO_EOC 0x20 |
end of command More... | |
#define | PROTO_OK 0x10 |
INSYNC/OK - 'ok' response. More... | |
#define | PROTO_FAILED 0x11 |
INSYNC/FAILED - 'fail' response. More... | |
#define | PROTO_INVALID 0x13 |
INSYNC/INVALID - 'invalid' response for bad commands. More... | |
#define | PROTO_GET_SYNC 0x21 |
NOP for re-establishing sync. More... | |
#define | PROTO_GET_DEVICE 0x22 |
get device ID bytes More... | |
#define | PROTO_CHIP_ERASE 0x23 |
erase program area and reset program address More... | |
#define | PROTO_CHIP_VERIFY 0x24 |
set next programming address More... | |
#define | PROTO_PROG_MULTI 0x27 |
write bytes at program address and increment More... | |
#define | PROTO_GET_CRC 0x29 |
compute & return a CRC More... | |
#define | PROTO_BOOT 0x30 |
boot the application More... | |
Functions | |
void | px4flash_init (void) |
void | px4flash_event (void) |
Variables | |
bool | setToBootloaderMode |
bool | px4ioRebootTimeout |
Definition in file px4_flash.c.
#define FLASH_PORT (&((FLASH_UART).device)) |
Definition at line 51 of file px4_flash.c.
#define PROTO_BOOT 0x30 |
boot the application
Definition at line 74 of file px4_flash.c.
#define PROTO_CHIP_ERASE 0x23 |
erase program area and reset program address
Definition at line 70 of file px4_flash.c.
#define PROTO_CHIP_VERIFY 0x24 |
set next programming address
Definition at line 71 of file px4_flash.c.
#define PROTO_EOC 0x20 |
end of command
Definition at line 62 of file px4_flash.c.
#define PROTO_FAILED 0x11 |
INSYNC/FAILED - 'fail' response.
Definition at line 65 of file px4_flash.c.
#define PROTO_GET_CRC 0x29 |
compute & return a CRC
Definition at line 73 of file px4_flash.c.
#define PROTO_GET_DEVICE 0x22 |
get device ID bytes
Definition at line 69 of file px4_flash.c.
#define PROTO_GET_SYNC 0x21 |
NOP for re-establishing sync.
Definition at line 68 of file px4_flash.c.
#define PROTO_INSYNC 0x12 |
'in sync' byte sent before status
Definition at line 61 of file px4_flash.c.
#define PROTO_INVALID 0x13 |
INSYNC/INVALID - 'invalid' response for bad commands.
Definition at line 66 of file px4_flash.c.
#define PROTO_OK 0x10 |
INSYNC/OK - 'ok' response.
Definition at line 64 of file px4_flash.c.
#define PROTO_PROG_MULTI 0x27 |
write bytes at program address and increment
Definition at line 72 of file px4_flash.c.
#define PX4_IO_FORCE_PROG FALSE |
Definition at line 54 of file px4_flash.c.
void px4flash_event | ( | void | ) |
Definition at line 88 of file px4_flash.c.
References b, B115200, B230400, char_available(), IOPacket::count_code, IOPacket::crc, crc_packet(), FALSE, FLASH_PORT, intermcu_set_enabled(), mcu_reboot(), MCU_REBOOT_BOOTLOADER, IOPacket::offset, p, IOPacket::page, PKT_CODE_SUCCESS, PROTO_EOC, PROTO_GET_SYNC, PROTO_INSYNC, PROTO_OK, PX4IO_P_SETUP_REBOOT_BL, PX4IO_PAGE_SETUP, PX4IO_REBOOT_BL_MAGIC, px4ioRebootTimeout, IOPacket::regs, setToBootloaderMode, state, sys_time_cancel_timer(), sys_time_check_and_ack_timer(), sys_time_usleep(), target, TRUE, and uart_periph_set_baudrate().
void px4flash_init | ( | void | ) |
Definition at line 79 of file px4_flash.c.
References px4ioRebootTimeout, setToBootloaderMode, and sys_time_register_timer().
bool px4ioRebootTimeout |
Definition at line 77 of file px4_flash.c.
Referenced by px4flash_event(), and px4flash_init().
bool setToBootloaderMode |
Definition at line 76 of file px4_flash.c.
Referenced by px4flash_event(), and px4flash_init().