|
|
@ -27,72 +27,44 @@ using namespace Linux; |
|
|
|
|
|
|
|
|
|
|
|
UtilRPI::UtilRPI() |
|
|
|
UtilRPI::UtilRPI() |
|
|
|
{ |
|
|
|
{ |
|
|
|
_check_rpi_version(); |
|
|
|
_check_rpi_version_by_rev(); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
int UtilRPI::_check_rpi_version() |
|
|
|
int UtilRPI::_check_rpi_version_by_rev() |
|
|
|
{ |
|
|
|
{ |
|
|
|
const unsigned int MAX_SIZE_LINE = 50; |
|
|
|
// assume 2 if unknown
|
|
|
|
char buffer[MAX_SIZE_LINE]; |
|
|
|
_rpi_version = 2; |
|
|
|
int hw; |
|
|
|
const char *SOC[]= {"Broadcom BCM2835","Broadcom BCM2836","Broadcom BCM2837","Broadcom BCM2711"}; |
|
|
|
|
|
|
|
const char *revision_file_ = "/proc/device-tree/system/linux,revision"; |
|
|
|
|
|
|
|
uint8_t revision[4] = { 0 }; |
|
|
|
|
|
|
|
uint32_t cpu = 0; |
|
|
|
|
|
|
|
FILE *fd; |
|
|
|
|
|
|
|
|
|
|
|
memset(buffer, 0, MAX_SIZE_LINE); |
|
|
|
if ((fd = fopen(revision_file_, "rb")) == NULL) { |
|
|
|
FILE *f = fopen("/sys/firmware/devicetree/base/model", "r"); |
|
|
|
printf("Can't open '%s'\n", revision_file_); |
|
|
|
if (f != nullptr && fgets(buffer, MAX_SIZE_LINE, f) != nullptr) { |
|
|
|
} |
|
|
|
fclose(f); |
|
|
|
else { |
|
|
|
|
|
|
|
if (fread(revision, 1, sizeof(revision), fd) == 4) { |
|
|
|
int ret = strncmp(buffer, "Raspberry Pi Compute Module 4", 28); |
|
|
|
cpu = (revision[2] >> 4) & 0xf; |
|
|
|
if (ret == 0) { |
|
|
|
|
|
|
|
_rpi_version = 4; // compute module 4 e.g. Raspberry Pi Compute Module 4 Rev 1.0.
|
|
|
|
_rpi_version = cpu; |
|
|
|
printf("%s. (intern: %d)\n", buffer, _rpi_version); |
|
|
|
|
|
|
|
return _rpi_version; |
|
|
|
if (_rpi_version==0) { |
|
|
|
} |
|
|
|
_rpi_version=1; //RPI-Zero
|
|
|
|
|
|
|
|
|
|
|
|
ret = strncmp(buffer, "Raspberry Pi Zero 2", 19); |
|
|
|
|
|
|
|
if (ret == 0) { |
|
|
|
|
|
|
|
_rpi_version = 2; // Raspberry PI Zero 2 W e.g. Raspberry Pi Zero 2 Rev 1.0.
|
|
|
|
|
|
|
|
printf("%s. (intern: %d)\n", buffer, _rpi_version); |
|
|
|
|
|
|
|
return _rpi_version; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
ret = sscanf(buffer + 12, "%d", &_rpi_version); |
|
|
|
|
|
|
|
if (ret != EOF) { |
|
|
|
|
|
|
|
if (_rpi_version > 3) { |
|
|
|
|
|
|
|
_rpi_version = 4; |
|
|
|
|
|
|
|
} else if (_rpi_version > 2) { |
|
|
|
|
|
|
|
// 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; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
printf("%s. (intern: %d)\n", buffer, _rpi_version); |
|
|
|
printf("SOC: %s use intern: %d \r\n",SOC[cpu], _rpi_version); |
|
|
|
|
|
|
|
|
|
|
|
return _rpi_version; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
else { |
|
|
|
|
|
|
|
printf("Revision data too short\n"); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
fclose(fd); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// Attempting old method if the version couldn't be read with the new one.
|
|
|
|
|
|
|
|
hw = Util::from(hal.util)->get_hw_arm32(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (hw == UTIL_HARDWARE_RPI4) { |
|
|
|
|
|
|
|
printf("Raspberry Pi 4 with BCM2711!\n"); |
|
|
|
|
|
|
|
_rpi_version = 4; |
|
|
|
|
|
|
|
} else if (hw == UTIL_HARDWARE_RPI2) { |
|
|
|
|
|
|
|
printf("Raspberry Pi 2/3 with BCM2709!\n"); |
|
|
|
|
|
|
|
_rpi_version = 2; |
|
|
|
|
|
|
|
} else if (hw == UTIL_HARDWARE_RPI1) { |
|
|
|
|
|
|
|
printf("Raspberry Pi 1 with BCM2708!\n"); |
|
|
|
|
|
|
|
_rpi_version = 1; |
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
/* defaults to RPi version 2/3 */ |
|
|
|
|
|
|
|
fprintf(stderr, "Could not detect RPi version, defaulting to 2/3\n"); |
|
|
|
|
|
|
|
_rpi_version = 2; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
return _rpi_version; |
|
|
|
return _rpi_version; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int UtilRPI::get_rpi_version() const |
|
|
|
int UtilRPI::get_rpi_version() const |
|
|
|
{ |
|
|
|
{ |
|
|
|
return _rpi_version; |
|
|
|
return _rpi_version; |
|
|
|