From 14b29cf7dee10729577677e065b2376c4c50dbba Mon Sep 17 00:00:00 2001
From: Peter Barker <pbarker@barker.dropbear.id.au>
Date: Fri, 13 Dec 2024 20:15:44 +1100
Subject: [PATCH] AP_FlashStorage: remove superfluous linefeed from panic
 strings

panic adds this within the HAL layer.
---
 .../examples/FlashTest/FlashTest.cpp             | 16 ++++++++--------
 1 file changed, 8 insertions(+), 8 deletions(-)

diff --git a/libraries/AP_FlashStorage/examples/FlashTest/FlashTest.cpp b/libraries/AP_FlashStorage/examples/FlashTest/FlashTest.cpp
index f617b4850a..fe76f28429 100644
--- a/libraries/AP_FlashStorage/examples/FlashTest/FlashTest.cpp
+++ b/libraries/AP_FlashStorage/examples/FlashTest/FlashTest.cpp
@@ -46,17 +46,17 @@ private:
 bool FlashTest::flash_write(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length)
 {
     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) {
-        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)offset,
                       (unsigned)length);
     }
     uint8_t *b = &flash[sector][offset];
     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)offset,
                       (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]);
         uint16_t v2 = le16toh_ptr(&b[i*2]);
         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(offset+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
         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(offset+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)
 {
     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) {
-        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)offset,
                       (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)
 {
     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);
     return true;