Skip to content
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

Added memory classes #12379

Merged
merged 5 commits into from Sep 30, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
18 changes: 16 additions & 2 deletions libraries/AP_HAL/AP_HAL_Boards.h
Expand Up @@ -92,13 +92,27 @@
/* CPU classes, used to select if CPU intensive algorithms should be used
* Note that these are only approximate, not exact CPU speeds. */

/* 150Mhz: PX4 or similar. Assumes:
/* 150Mhz: STM32F4 or similar. Assumes:
* - hardware floating point
* - tens of kilobytes of memory available */
* - tens of kilobytes of memory available
*/
#define HAL_CPU_CLASS_150 3

/* GigaHz class: SITL, BeagleBone etc. Assumes megabytes of memory available. */
#define HAL_CPU_CLASS_1000 4


/*
memory classes, in kbytes. Board must have at least the given amount
of memory
*/
#define HAL_MEM_CLASS_20 1
#define HAL_MEM_CLASS_64 2
#define HAL_MEM_CLASS_192 3
#define HAL_MEM_CLASS_300 4
#define HAL_MEM_CLASS_500 5
#define HAL_MEM_CLASS_1000 6

/* Operating system features
*
* HAL implementations may define the following extra feature defines to 1 if
Expand Down
15 changes: 14 additions & 1 deletion libraries/AP_HAL/board/chibios.h
Expand Up @@ -4,7 +4,20 @@
#include <hal.h>

#define HAL_BOARD_NAME "ChibiOS"
#define HAL_CPU_CLASS HAL_CPU_CLASS_150

#if HAL_MEMORY_TOTAL_KB >= 1000
#define HAL_MEM_CLASS HAL_MEM_CLASS_1000
#elif HAL_MEMORY_TOTAL_KB >= 500
#define HAL_MEM_CLASS HAL_MEM_CLASS_500
#elif HAL_MEMORY_TOTAL_KB >= 300
#define HAL_MEM_CLASS HAL_MEM_CLASS_300
#elif HAL_MEMORY_TOTAL_KB >= 192
#define HAL_MEM_CLASS HAL_MEM_CLASS_192
#elif HAL_MEMORY_TOTAL_KB >= 64
#define HAL_MEM_CLASS HAL_MEM_CLASS_64
#else
#define HAL_MEM_CLASS HAL_MEM_CLASS_20
#endif

#ifndef HAL_GPIO_LED_ON
#define HAL_GPIO_LED_ON 0
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL/board/empty.h
Expand Up @@ -2,6 +2,7 @@

#define HAL_BOARD_NAME "EMPTY"
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
#define HAL_MEM_CLASS HAL_MEM_CLASS_192
#define HAL_STORAGE_SIZE 16384
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
#define HAL_INS_DEFAULT HAL_INS_HIL
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL/board/linux.h
Expand Up @@ -2,6 +2,7 @@

#define HAL_BOARD_NAME "Linux"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_MEM_CLASS HAL_MEM_CLASS_1000
#define HAL_OS_POSIX_IO 1
#define HAL_OS_SOCKETS 1
#define HAL_STORAGE_SIZE 16384
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL/board/sitl.h
Expand Up @@ -2,6 +2,7 @@

#define HAL_BOARD_NAME "SITL"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_MEM_CLASS HAL_MEM_CLASS_1000
#define HAL_OS_POSIX_IO 1
#define HAL_OS_SOCKETS 1
#define HAL_STORAGE_SIZE 16384
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py
Expand Up @@ -596,9 +596,12 @@ def write_mcu_config(f):
ram_map = get_mcu_config('RAM_MAP', True)
f.write('// memory regions\n')
regions = []
total_memory = 0
for (address, size, flags) in ram_map:
regions.append('{(void*)0x%08x, 0x%08x, 0x%02x }' % (address, size*1024, flags))
total_memory += size
f.write('#define HAL_MEMORY_REGIONS %s\n' % ', '.join(regions))
f.write('#define HAL_MEMORY_TOTAL_KB %u\n' % total_memory)

f.write('\n// CPU serial number (12 bytes)\n')
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_Logger/AP_Logger.cpp
Expand Up @@ -15,8 +15,12 @@ AP_Logger *AP_Logger::_singleton;
extern const AP_HAL::HAL& hal;

#ifndef HAL_LOGGING_FILE_BUFSIZE
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_300
#define HAL_LOGGING_FILE_BUFSIZE 50
#else
#define HAL_LOGGING_FILE_BUFSIZE 16
#endif
#endif
#endif

#ifndef HAL_LOGGING_MAV_BUFSIZE
#define HAL_LOGGING_MAV_BUFSIZE 8
Expand Down
8 changes: 6 additions & 2 deletions libraries/AP_Logger/AP_Logger_File.cpp
Expand Up @@ -83,10 +83,14 @@ void AP_Logger_File::Init()
}
bufsize *= 1024;

const uint32_t desired_bufsize = bufsize;

// If we can't allocate the full size, try to reduce it until we can allocate it
while (!_writebuf.set_size(bufsize) && bufsize >= _writebuf_chunk) {
hal.console->printf("AP_Logger_File: Couldn't set buffer size to=%u\n", (unsigned)bufsize);
bufsize >>= 1;
bufsize *= 0.9;
}
if (bufsize >= _writebuf_chunk && bufsize != desired_bufsize) {
hal.console->printf("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize, (unsigned)desired_bufsize);
}

if (!_writebuf.get_size()) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Expand Up @@ -812,7 +812,7 @@ class GCS

void update_sensor_status_flags();

#if HAL_CPU_CLASS <= HAL_CPU_CLASS_150 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if HAL_MEM_CLASS <= HAL_MEM_CLASS_192 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
static const uint8_t _status_capacity = 5;
#else
static const uint8_t _status_capacity = 30;
Expand Down