2015-09-23 12:52:07 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
2015-11-28 05:38:56 -04:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
2016-01-20 09:27:43 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
|
2016-06-29 05:16:03 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE || \
|
2015-11-28 05:38:56 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
2016-01-05 06:36:02 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
2016-10-17 15:02:48 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
|
2020-01-10 15:25:03 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI || \
|
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR
|
2015-09-23 12:52:07 -03:00
|
|
|
|
2018-02-12 13:05:21 -04:00
|
|
|
#include <errno.h>
|
2015-09-23 12:52:07 -03:00
|
|
|
#include <stdarg.h>
|
2018-02-12 13:05:21 -04:00
|
|
|
#include <stdio.h>
|
2015-09-23 12:52:07 -03:00
|
|
|
#include <stdlib.h>
|
2018-02-12 13:05:21 -04:00
|
|
|
#include <sys/stat.h>
|
2015-09-23 12:52:07 -03:00
|
|
|
#include <time.h>
|
2018-02-12 13:05:21 -04:00
|
|
|
#include <unistd.h>
|
2015-09-23 12:52:07 -03:00
|
|
|
|
2015-12-22 09:49:12 -04:00
|
|
|
#include "Util.h"
|
2018-02-12 13:05:21 -04:00
|
|
|
#include "Util_RPI.h"
|
2015-09-23 12:52:07 -03:00
|
|
|
|
2018-02-12 13:05:21 -04:00
|
|
|
extern const AP_HAL::HAL &hal;
|
2015-09-23 12:52:07 -03:00
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
UtilRPI::UtilRPI()
|
2015-09-23 12:52:07 -03:00
|
|
|
{
|
|
|
|
_check_rpi_version();
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int UtilRPI::_check_rpi_version()
|
2015-09-23 12:52:07 -03:00
|
|
|
{
|
2018-02-12 12:46:36 -04:00
|
|
|
const unsigned int MAX_SIZE_LINE = 50;
|
|
|
|
char buffer[MAX_SIZE_LINE];
|
2015-12-22 09:49:12 -04:00
|
|
|
int hw;
|
2017-12-06 08:04:06 -04:00
|
|
|
|
2018-02-12 12:46:36 -04:00
|
|
|
FILE *f = fopen("/sys/firmware/devicetree/base/model", "r");
|
2017-12-06 08:04:06 -04:00
|
|
|
if (f != nullptr && fgets(buffer, MAX_SIZE_LINE, f) != nullptr) {
|
2018-02-12 12:46:36 -04:00
|
|
|
int ret = sscanf(buffer + 12, "%d", &_rpi_version);
|
|
|
|
fclose(f);
|
|
|
|
if (ret != EOF) {
|
2020-01-10 09:53:38 -04:00
|
|
|
if (_rpi_version > 3) {
|
|
|
|
_rpi_version = 4;
|
|
|
|
} else if (_rpi_version > 2) {
|
2018-02-12 12:46:36 -04:00
|
|
|
// Preserving old behavior.
|
|
|
|
_rpi_version = 2;
|
|
|
|
} else if (_rpi_version == 0) {
|
|
|
|
// RPi 1 doesn't have a number there, so sscanf() won't have read anything.
|
|
|
|
_rpi_version = 1;
|
|
|
|
}
|
2017-12-06 08:04:06 -04:00
|
|
|
|
2018-02-12 12:46:36 -04:00
|
|
|
printf("%s. (intern: %d)\n", buffer, _rpi_version);
|
2017-12-06 08:04:06 -04:00
|
|
|
|
2018-02-12 12:46:36 -04:00
|
|
|
return _rpi_version;
|
|
|
|
}
|
|
|
|
}
|
2017-12-06 08:04:06 -04:00
|
|
|
|
|
|
|
// Attempting old method if the version couldn't be read with the new one.
|
2015-12-22 09:49:12 -04:00
|
|
|
hw = Util::from(hal.util)->get_hw_arm32();
|
|
|
|
|
2020-01-10 09:53:38 -04:00
|
|
|
if (hw == UTIL_HARDWARE_RPI4) {
|
|
|
|
printf("Raspberry Pi 4 with BCM2711!\n");
|
|
|
|
_rpi_version = 4;
|
|
|
|
} else if (hw == UTIL_HARDWARE_RPI2) {
|
2016-06-06 11:38:51 -03:00
|
|
|
printf("Raspberry Pi 2/3 with BCM2709!\n");
|
2015-12-22 09:49:12 -04:00
|
|
|
_rpi_version = 2;
|
|
|
|
} else if (hw == UTIL_HARDWARE_RPI1) {
|
|
|
|
printf("Raspberry Pi 1 with BCM2708!\n");
|
|
|
|
_rpi_version = 1;
|
|
|
|
} else {
|
2016-06-06 11:38:51 -03:00
|
|
|
/* defaults to RPi version 2/3 */
|
|
|
|
fprintf(stderr, "Could not detect RPi version, defaulting to 2/3\n");
|
|
|
|
_rpi_version = 2;
|
2015-09-23 12:52:07 -03:00
|
|
|
}
|
|
|
|
return _rpi_version;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int UtilRPI::get_rpi_version() const
|
2015-09-23 12:52:07 -03:00
|
|
|
{
|
|
|
|
return _rpi_version;
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|