mirror of https://github.com/ArduPilot/ardupilot
AP_FlashStorage: remove superfluous linefeed from panic strings
panic adds this within the HAL layer.
This commit is contained in:
parent
f59efb8a19
commit
14b29cf7de
|
@ -46,17 +46,17 @@ private:
|
||||||
bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
|
bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
|
||||||
{
|
{
|
||||||
if (sector > 1) {
|
if (sector > 1) {
|
||||||
AP_HAL::panic("FATAL: write to sector %u\n", (unsigned)sector);
|
AP_HAL::panic("FATAL: write to sector %u", (unsigned)sector);
|
||||||
}
|
}
|
||||||
if (offset + length > flash_sector_size) {
|
if (offset + length > flash_sector_size) {
|
||||||
AP_HAL::panic("FATAL: write to sector %u at offset %u length %u\n",
|
AP_HAL::panic("FATAL: write to sector %u at offset %u length %u",
|
||||||
(unsigned)sector,
|
(unsigned)sector,
|
||||||
(unsigned)offset,
|
(unsigned)offset,
|
||||||
(unsigned)length);
|
(unsigned)length);
|
||||||
}
|
}
|
||||||
uint8_t *b = &flash[sector][offset];
|
uint8_t *b = &flash[sector][offset];
|
||||||
if ((offset & 1) || (length & 1)) {
|
if ((offset & 1) || (length & 1)) {
|
||||||
AP_HAL::panic("FATAL: invalid write at %u:%u len=%u\n",
|
AP_HAL::panic("FATAL: invalid write at %u:%u len=%u",
|
||||||
(unsigned)sector,
|
(unsigned)sector,
|
||||||
(unsigned)offset,
|
(unsigned)offset,
|
||||||
(unsigned)length);
|
(unsigned)length);
|
||||||
|
@ -66,7 +66,7 @@ bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data
|
||||||
const uint16_t v = le16toh_ptr(&data[i*2]);
|
const uint16_t v = le16toh_ptr(&data[i*2]);
|
||||||
uint16_t v2 = le16toh_ptr(&b[i*2]);
|
uint16_t v2 = le16toh_ptr(&b[i*2]);
|
||||||
if (v & !v2) {
|
if (v & !v2) {
|
||||||
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x\n",
|
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x",
|
||||||
(unsigned)sector,
|
(unsigned)sector,
|
||||||
unsigned(offset+i),
|
unsigned(offset+i),
|
||||||
b[i],
|
b[i],
|
||||||
|
@ -74,7 +74,7 @@ bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data
|
||||||
}
|
}
|
||||||
#ifndef AP_FLASHSTORAGE_MULTI_WRITE
|
#ifndef AP_FLASHSTORAGE_MULTI_WRITE
|
||||||
if (v != v2 && v != 0xFFFF && v2 != 0xFFFF) {
|
if (v != v2 && v != 0xFFFF && v2 != 0xFFFF) {
|
||||||
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x\n",
|
AP_HAL::panic("FATAL: invalid write16 at %u:%u 0x%04x 0x%04x",
|
||||||
(unsigned)sector,
|
(unsigned)sector,
|
||||||
unsigned(offset+i),
|
unsigned(offset+i),
|
||||||
b[i],
|
b[i],
|
||||||
|
@ -90,10 +90,10 @@ bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data
|
||||||
bool FlashTest::flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
|
bool FlashTest::flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length)
|
||||||
{
|
{
|
||||||
if (sector > 1) {
|
if (sector > 1) {
|
||||||
AP_HAL::panic("FATAL: read from sector %u\n", (unsigned)sector);
|
AP_HAL::panic("FATAL: read from sector %u", (unsigned)sector);
|
||||||
}
|
}
|
||||||
if (offset + length > flash_sector_size) {
|
if (offset + length > flash_sector_size) {
|
||||||
AP_HAL::panic("FATAL: read from sector %u at offset %u length %u\n",
|
AP_HAL::panic("FATAL: read from sector %u at offset %u length %u",
|
||||||
(unsigned)sector,
|
(unsigned)sector,
|
||||||
(unsigned)offset,
|
(unsigned)offset,
|
||||||
(unsigned)length);
|
(unsigned)length);
|
||||||
|
@ -105,7 +105,7 @@ bool FlashTest::flash_read(uint8_t sector, uint32_t offset, uint8_t *data, uint1
|
||||||
bool FlashTest::flash_erase(uint8_t sector)
|
bool FlashTest::flash_erase(uint8_t sector)
|
||||||
{
|
{
|
||||||
if (sector > 1) {
|
if (sector > 1) {
|
||||||
AP_HAL::panic("FATAL: erase sector %u\n", (unsigned)sector);
|
AP_HAL::panic("FATAL: erase sector %u", (unsigned)sector);
|
||||||
}
|
}
|
||||||
memset(&flash[sector][0], 0xFF, flash_sector_size);
|
memset(&flash[sector][0], 0xFF, flash_sector_size);
|
||||||
return true;
|
return true;
|
||||||
|
|
Loading…
Reference in New Issue