New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Clean up and extend RAMTRON driver #13621
Conversation
thanks for your work on this! |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
thanks for your work on this!
A few changes needed are listed below, plus I'd like to add the retries from #13581. That PR came out of a board where power up speed seems to cause the init of the ramtron to fail sometimes. I don't think the result is explained by your changes.
libraries/AP_Param/AP_Param.h
Outdated
@@ -517,7 +517,8 @@ class AP_Param | |||
uint8_t magic[2]; | |||
uint8_t revision; | |||
uint8_t spare; | |||
}; | |||
} PACKED; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
adding PACKED on this structure doesn't change the shape for storage, but does make g++ produce less efficient code (it makes for larger flash size for no advantage)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is a habit from working with space constrained devices. Removed the PACKED attribute.
libraries/AP_Param/AP_Param.h
Outdated
@@ -539,7 +540,8 @@ class AP_Param | |||
uint32_t type : 5; | |||
uint32_t key_high : 1; | |||
uint32_t group_element : 18; | |||
}; | |||
} PACKED; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
same here, PACKED just makes for less efficient code
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Removed the PACKED attribute.
libraries/AP_RAMTRON/AP_RAMTRON.cpp
Outdated
uint8_t manufacturer[6]; | ||
uint8_t memory; | ||
uint8_t id1; | ||
uint8_t id2; | ||
} rdid; | ||
if (!dev->read_registers(RAMTRON_RDID, (uint8_t *)&rdid, sizeof(rdid))) { | ||
} PACKED; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
PACKED doesn't help here and makes for slower and larger code
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Removed the PACKED attribute. Replaced with a static_assert
to ensure the RDID
shape is correct.
libraries/AP_RAMTRON/AP_RAMTRON.cpp
Outdated
uint8_t manufacturer[2]; | ||
uint8_t id1; | ||
uint8_t id2; | ||
} PACKED; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
PACKED doesn't help
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
As above, removed PACKED attribute, added static_assert
.
ArduPlane/Parameters.cpp
Outdated
@@ -45,7 +45,7 @@ const AP_Param::Info Plane::var_info[] = { | |||
ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6), | |||
|
|||
// @Param: TELEM_DELAY | |||
// @DisplayName: Telemetry startup delay |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
could you see if you can configure your editor not to do whitespace cleanup on lines you don't edit?
You may find using "git add -p" to build a patchset useful.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ack. Once you're happy with the changes, I'll rebase and remove the whitespace changes.
Are you aware that you can append ?w=1
to the URL to hide whitespace changes in the diff? Maybe you can do this in the interim?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
yes, I'm aware. It just pollutes commits however, changing the git blame results
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Rebased to remove the whitepace changes.
libraries/AP_RAMTRON/AP_RAMTRON.h
Outdated
|
||
// read from device | ||
bool read(uint32_t offset, uint8_t *buf, uint32_t size); | ||
uint32_t read(uint32_t offset, uint8_t * const buf, uint32_t size); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
why change from bool when the only use case is to check if we get the full amount requested?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
It was useful while I was debugging to see why I wasn't getting back the data I expected. It also allows consumers to do partial retries.
Would you prefer this reverted back to returning a bool
?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
yes, I'd prefer it be bool. If we end up with a consumer that wants to do partial retries in the future we could change this, but I doubt we will
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Reverted to bool
.
libraries/AP_RAMTRON/AP_RAMTRON.h
Outdated
|
||
// write to device | ||
bool write(uint32_t offset, const uint8_t *buf, uint32_t size); | ||
uint32_t write(uint32_t offset, uint8_t const * const buf, uint32_t size); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
why change from bool?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
As above...
libraries/AP_RAMTRON/AP_RAMTRON.cpp
Outdated
// get data | ||
dev->transfer(nullptr, 0, buf, size); | ||
uint32_t const kReadSz = MIN(size, kMaxReadSz); | ||
bool ok = dev->set_chip_select(true); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
transfer() already handles chip select, so is only needed when doing multiple operations within the one CS op
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Removed the unnecessary calls to set_chip_select()
.
libraries/AP_HAL_ChibiOS/Storage.cpp
Outdated
if (fram.read(0, _buffer, CH_STORAGE_SIZE) == CH_STORAGE_SIZE) { | ||
_save_backup(); | ||
_initialisedType = StorageBackend::FRAM; | ||
hal.console->printf("Initialised Storage type=%d\n", _initialisedType); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
this happens so early that it isn't visible on the console as console isn't setup yet
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Changed back to using ::printf()
libraries/AP_HAL_ChibiOS/Storage.cpp
Outdated
if (sdcard_retry()) { | ||
log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT); | ||
if (log_fd == -1) { | ||
hal.console->printf("open failed of " HAL_STORAGE_FILE "\n"); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
::printf() was used as it works in early startup
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ack. As above, reverted to use ::printf()
I've 3 fmuv3 boards, pixhawk1 like, which do not save any parameters. On this pull request it gives "Couldn't load params: erasing params..." |
Please note: The latest changes compile, but I won't have a chance to test them on the relevant hardware until tomorrow. |
libraries/AP_HAL_ChibiOS/Storage.cpp
Outdated
} | ||
|
||
#if defined(HAL_RAMTRON_ALLOW_FALLBACK) && !HAL_RAMTRON_ALLOW_FALLBACK | ||
AP_HAL::panic("Unable to init RAMTRON storage"); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Looks like your indentation has gone wonky here
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Fixed.
libraries/AP_HAL_ChibiOS/Storage.h
Outdated
@@ -48,7 +48,13 @@ class ChibiOS::Storage : public AP_HAL::Storage { | |||
bool healthy(void) override; | |||
|
|||
private: | |||
volatile bool _initialised; | |||
enum StorageBackend { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
enum class
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Fixed.
libraries/AP_HAL_ChibiOS/Storage.h
Outdated
Flash, | ||
SDCard, | ||
}; | ||
volatile enum StorageBackend _initialisedType = StorageBackend::None; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
don't think you need the enum here
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Don't need the enum
now that StorageBackend
is an enum class
. Fixed.
We had another report in the forums of this happening. It very often seems to happen as part of a firmware upgrade. https://discuss.ardupilot.org/t/all-parameters-set-to-default-by-themselves/52983 |
While they share the same register maps, the FRAM devices from Cypress and Fujitsu return a different data structure when the RDID register is read.
This driver will panic if HAL_RAMTRON_NO_FALLBACK is defined in the hwdef.dat file and the RAMTRON initialisation fails. This prevents us from silently falling back to a potentially different parameter set and causing unexpected behaviour.
…is used Note: This usually won't get seen as the USB is not up when this is printed. However, adding a delay (of ~2s) into the main_loop() function in the HAL_ChibiOS_Class.cpp, just after the scheduler is initialised, will allow this message to be seen.
…efined This #error pragma causes the Bootloader to fail, even though this file class isn't used by the Bootloader. However, it is included in the base AP_HAL definition that the Bootloader pulls in.
Inline initialisation of VLAs will cause a compilation error under Clang, as it is not allowed according to the C specification. However, GCC will allow it.
::printf() is available earlier than hal.console->printf() during boot.
Change from HAL_RAMTRON_NO_FALLBACK to HAL_RAMTRON_ALLOW_FALLBACK.
This adds equivalent functionality that was originally added in: ArduPilot#13581
This adds equivalent functionality that was originally added in: ArduPilot#13581
@tridge: I've incorporated equivalent changes to #13581 in commits 2dc533a and 528fe35. |
Tidied up and rebased onto latest |
@sypaq-nexton the main holdup on this PR now is the investigation we have going on into the param resets on cube orange. The changes you have done unfortunately don't explain the issue. We're seeing params reset with a firmware that only has RAMTRON storage enabled, and with a firmware that does every read twice to confirm with CRC. Most bizarrely we're seeing resets even when we completely remove the write() code in the ramtron driver, so it should have no ability to write to the ramtron at all. |
@sypaq-nexton we've now proven that CS pin floating in the bootloader is the cause of the resets that have particulatly plagued cube orange. We will still do the improvements to the RAMTRON driver, but the key fix seems to be this one: #13780 |
@sypaq-nexton I did tests of this branch on a CubeBlack and found that parameters did not persist. The change of approach for the latching of the write enable bit of the FRAM doesn't work on that cypress chip. It is also dangerous as it leaves write enabled as the normal state when flying which means that on reboot the floating CS pin is much more likely to cause corruption. |
Great, thanks @tridge! |
We experienced an issue where parameters were being unexpectedly erased during development. The sequence of events that caused this was:
This behaviour was observed on both a Pixracer and custom hardware.
The root cause of the the RAMTRON driver failing to initialise (step 1. above) was different data returned by different manufacturers. Fujitsu and Cypress make FRAM chips that are both pin and register compatible, but each manufacturer returns different data when the
RDID
register is read.This pull request contains the following key changes to address the issues discovered during this investigation:
RDID
format. This was then used to properly parse the read of theRDID
register.init
function to ensure theWriteEnable
andBlockProtect
bits of the status register are properly set.read
andwrite
functions so that the SPI read and write calls were inside the same chip select activation. This prevents spurious data being returned if the FRAM chip resets it's read registers on deselect.read
andwrite
functions to fail if we attempt to access more data than the FRAM chip can hold. Previously these would silently wrap back to address0x0000
, which would cause unexpected behaviour.hwdef.dat
file) that prevents falling back to another device if the FRAM can't be initialised.Please let me know if you need test evidence and/or test cases for this.