mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
DataFlash: parameterise dataflash-over-mavlink cachesize
This commit is contained in:
parent
cb2e3424ee
commit
5bf2fb186c
@ -50,6 +50,13 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_FILE_DSRMROT", 4, DataFlash_Class, _params.file_disarm_rot, 0),
|
AP_GROUPINFO("_FILE_DSRMROT", 4, DataFlash_Class, _params.file_disarm_rot, 0),
|
||||||
|
|
||||||
|
// @Param: _MAV_BUFSIZE
|
||||||
|
// @DisplayName: Maximum DataFlash MAVLink Backend buffer size
|
||||||
|
// @Description: Maximum amount of memory to allocate to DataFlash-over-mavlink
|
||||||
|
// @User: Advanced
|
||||||
|
// @Units: kB
|
||||||
|
AP_GROUPINFO("_MAV_BUFSIZE", 5, DataFlash_Class, _params.mav_bufsize, 8),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -198,6 +198,7 @@ public:
|
|||||||
AP_Int8 file_disarm_rot;
|
AP_Int8 file_disarm_rot;
|
||||||
AP_Int8 log_disarmed;
|
AP_Int8 log_disarmed;
|
||||||
AP_Int8 log_replay;
|
AP_Int8 log_replay;
|
||||||
|
AP_Int8 mav_bufsize; // in kilobytes
|
||||||
} _params;
|
} _params;
|
||||||
|
|
||||||
const struct LogStructure *structure(uint16_t num) const;
|
const struct LogStructure *structure(uint16_t num) const;
|
||||||
|
@ -35,7 +35,7 @@ void DataFlash_MAVLink::Init()
|
|||||||
|
|
||||||
_blocks = nullptr;
|
_blocks = nullptr;
|
||||||
while (_blockcount >= 8) { // 8 is a *magic* number
|
while (_blockcount >= 8) { // 8 is a *magic* number
|
||||||
_blocks = (struct dm_block *) calloc(_blockcount, sizeof(_blocks[0]));
|
_blocks = (struct dm_block *) calloc(_blockcount, sizeof(struct dm_block));
|
||||||
if (_blocks != nullptr) {
|
if (_blocks != nullptr) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -23,10 +23,12 @@ public:
|
|||||||
// constructor
|
// constructor
|
||||||
DataFlash_MAVLink(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
|
DataFlash_MAVLink(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
|
||||||
DataFlash_Backend(front, writer),
|
DataFlash_Backend(front, writer),
|
||||||
_max_blocks_per_send_blocks(8),
|
_max_blocks_per_send_blocks(8)
|
||||||
_blockcount(32) // this may get reduced in Init if allocation fails
|
|
||||||
,_perf_packing(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DM_packing"))
|
,_perf_packing(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "DM_packing"))
|
||||||
{ }
|
{
|
||||||
|
_blockcount = 1024*((uint8_t)_front._params.mav_bufsize) / sizeof(struct dm_block);
|
||||||
|
// ::fprintf(stderr, "DM: Using %u blocks\n", _blockcount);
|
||||||
|
}
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
void Init() override;
|
void Init() override;
|
||||||
|
Loading…
Reference in New Issue
Block a user