mirror of https://github.com/ArduPilot/ardupilot
StorageManager: add read_float and write_float
This commit is contained in:
parent
67fea9f2f8
commit
e644a9dda8
|
@ -265,6 +265,16 @@ uint32_t StorageAccess::read_uint32(uint16_t loc) const
|
|||
return v;
|
||||
}
|
||||
|
||||
/*
|
||||
read a float
|
||||
*/
|
||||
float StorageAccess::read_float(uint16_t loc) const
|
||||
{
|
||||
float v;
|
||||
read_block(&v, loc, sizeof(v));
|
||||
return v;
|
||||
}
|
||||
|
||||
/*
|
||||
write a byte
|
||||
*/
|
||||
|
@ -289,6 +299,14 @@ void StorageAccess::write_uint32(uint16_t loc, uint32_t value) const
|
|||
write_block(loc, &value, sizeof(value));
|
||||
}
|
||||
|
||||
/*
|
||||
write a float
|
||||
*/
|
||||
void StorageAccess::write_float(uint16_t loc, float value) const
|
||||
{
|
||||
write_block(loc, &value, sizeof(value));
|
||||
}
|
||||
|
||||
/*
|
||||
copy one area to another
|
||||
*/
|
||||
|
|
|
@ -95,11 +95,13 @@ public:
|
|||
uint8_t read_uint8(uint16_t loc) const { return read_byte(loc); }
|
||||
uint16_t read_uint16(uint16_t loc) const;
|
||||
uint32_t read_uint32(uint16_t loc) const;
|
||||
float read_float(uint16_t loc) const;
|
||||
|
||||
void write_byte(uint16_t loc, uint8_t value) const;
|
||||
void write_uint8(uint16_t loc, uint8_t value) const { return write_byte(loc, value); }
|
||||
void write_uint16(uint16_t loc, uint16_t value) const;
|
||||
void write_uint32(uint16_t loc, uint32_t value) const;
|
||||
void write_float(uint16_t loc, float value) const;
|
||||
|
||||
// copy from one storage area to another
|
||||
bool copy_area(const StorageAccess &source) const;
|
||||
|
|
Loading…
Reference in New Issue