mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-20 06:43:56 -04:00
AP_HAL: make storage->write_block() take a const pointer
This commit is contained in:
parent
c008fa764c
commit
2316c3bd11
@ -16,7 +16,7 @@ public:
|
||||
virtual void write_byte(uint16_t loc, uint8_t value) = 0;
|
||||
virtual void write_word(uint16_t loc, uint16_t value) = 0;
|
||||
virtual void write_dword(uint16_t loc, uint32_t value) = 0;
|
||||
virtual void write_block(uint16_t dst, void* src, size_t n) = 0;
|
||||
virtual void write_block(uint16_t dst, const void* src, size_t n) = 0;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_STORAGE_H__
|
||||
|
@ -37,7 +37,7 @@ void AVREEPROMStorage::write_dword(uint16_t loc, uint32_t value) {
|
||||
write_block(loc, &value, sizeof(value));
|
||||
}
|
||||
|
||||
void AVREEPROMStorage::write_block(uint16_t dst, void *src, size_t n) {
|
||||
void AVREEPROMStorage::write_block(uint16_t dst, const void *src, size_t n) {
|
||||
uint8_t *p = (uint8_t *)src;
|
||||
while (n--) {
|
||||
write_byte(dst++, *p++);
|
||||
|
@ -18,7 +18,7 @@ public:
|
||||
void write_byte(uint16_t loc, uint8_t value);
|
||||
void write_word(uint16_t loc, uint16_t value);
|
||||
void write_dword(uint16_t loc, uint32_t value);
|
||||
void write_block(uint16_t dst, void* src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_AVR_STORAGE_H__
|
||||
|
@ -73,7 +73,7 @@ void SITLEEPROMStorage::write_dword(uint16_t loc, uint32_t value)
|
||||
assert(pwrite(_eeprom_fd, &value, 4, loc) == 4);
|
||||
}
|
||||
|
||||
void SITLEEPROMStorage::write_block(uint16_t dst, void *src, size_t n)
|
||||
void SITLEEPROMStorage::write_block(uint16_t dst, const void *src, size_t n)
|
||||
{
|
||||
assert(dst < 4096);
|
||||
_eeprom_open();
|
||||
|
@ -20,7 +20,7 @@ public:
|
||||
void write_byte(uint16_t loc, uint8_t value);
|
||||
void write_word(uint16_t loc, uint16_t value);
|
||||
void write_dword(uint16_t loc, uint32_t value);
|
||||
void write_block(uint16_t dst, void* src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
|
||||
private:
|
||||
int _eeprom_fd;
|
||||
|
@ -35,6 +35,6 @@ void EmptyStorage::write_word(uint16_t loc, uint16_t value)
|
||||
void EmptyStorage::write_dword(uint16_t loc, uint32_t value)
|
||||
{}
|
||||
|
||||
void EmptyStorage::write_block(uint16_t loc, void* src, size_t n)
|
||||
void EmptyStorage::write_block(uint16_t loc, const void* src, size_t n)
|
||||
{}
|
||||
|
||||
|
@ -16,7 +16,7 @@ public:
|
||||
void write_byte(uint16_t loc, uint8_t value);
|
||||
void write_word(uint16_t loc, uint16_t value);
|
||||
void write_dword(uint16_t loc, uint32_t value);
|
||||
void write_block(uint16_t dst, void* src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_EMPTY_STORAGE_H__
|
||||
|
@ -165,7 +165,7 @@ void PX4Storage::write_dword(uint16_t loc, uint32_t value)
|
||||
}
|
||||
}
|
||||
|
||||
void PX4Storage::write_block(uint16_t loc, void *src, size_t n)
|
||||
void PX4Storage::write_block(uint16_t loc, const void *src, size_t n)
|
||||
{
|
||||
if (loc >= sizeof(_buffer)-(n-1)) {
|
||||
return;
|
||||
|
@ -30,7 +30,7 @@ public:
|
||||
void write_byte(uint16_t loc, uint8_t value);
|
||||
void write_word(uint16_t loc, uint16_t value);
|
||||
void write_dword(uint16_t loc, uint32_t value);
|
||||
void write_block(uint16_t dst, void* src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
|
||||
void _timer_tick(void);
|
||||
|
||||
|
@ -78,7 +78,7 @@ void SMACCMStorage::write_dword(uint16_t loc, uint32_t value)
|
||||
eeprom_write(loc, (uint8_t*)&value, sizeof(value));
|
||||
}
|
||||
|
||||
void SMACCMStorage::write_block(uint16_t loc, void* src, size_t n)
|
||||
void SMACCMStorage::write_block(uint16_t loc, const void* src, size_t n)
|
||||
{
|
||||
eeprom_write(loc, (const uint8_t *)src, n);
|
||||
}
|
||||
|
@ -29,7 +29,7 @@ public:
|
||||
void write_byte(uint16_t loc, uint8_t value);
|
||||
void write_word(uint16_t loc, uint16_t value);
|
||||
void write_dword(uint16_t loc, uint32_t value);
|
||||
void write_block(uint16_t dst, void* src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_SMACCM_STORAGE_H__
|
||||
|
Loading…
Reference in New Issue
Block a user