APM:Libraries
Util_RPI.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
4  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \
5  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE || \
6  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
7  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
8  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
9  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
10 
11 #include <errno.h>
12 #include <stdarg.h>
13 #include <stdio.h>
14 #include <stdlib.h>
15 #include <sys/stat.h>
16 #include <time.h>
17 #include <unistd.h>
18 
19 #include "Util.h"
20 #include "Util_RPI.h"
21 
22 extern const AP_HAL::HAL &hal;
23 
24 using namespace Linux;
25 
27 {
29 }
30 
32 {
33  const unsigned int MAX_SIZE_LINE = 50;
34  char buffer[MAX_SIZE_LINE];
35  int hw;
36 
37  FILE *f = fopen("/sys/firmware/devicetree/base/model", "r");
38  if (f != nullptr && fgets(buffer, MAX_SIZE_LINE, f) != nullptr) {
39  int ret = sscanf(buffer + 12, "%d", &_rpi_version);
40  fclose(f);
41  if (ret != EOF) {
42 
43  if (_rpi_version > 2) {
44  // Preserving old behavior.
45  _rpi_version = 2;
46  } else if (_rpi_version == 0) {
47  // RPi 1 doesn't have a number there, so sscanf() won't have read anything.
48  _rpi_version = 1;
49  }
50 
51  printf("%s. (intern: %d)\n", buffer, _rpi_version);
52 
53  return _rpi_version;
54  }
55  }
56 
57  // Attempting old method if the version couldn't be read with the new one.
58  hw = Util::from(hal.util)->get_hw_arm32();
59 
60  if (hw == UTIL_HARDWARE_RPI2) {
61  printf("Raspberry Pi 2/3 with BCM2709!\n");
62  _rpi_version = 2;
63  } else if (hw == UTIL_HARDWARE_RPI1) {
64  printf("Raspberry Pi 1 with BCM2708!\n");
65  _rpi_version = 1;
66  } else {
67  /* defaults to RPi version 2/3 */
68  fprintf(stderr, "Could not detect RPi version, defaulting to 2/3\n");
69  _rpi_version = 2;
70  }
71  return _rpi_version;
72 }
73 
75 {
76  return _rpi_version;
77 }
78 
79 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
int _rpi_version
Definition: Util_RPI.h:23
AP_HAL::Util * util
Definition: HAL.h:115
#define MAX_SIZE_LINE
Definition: Util.cpp:184
static Util * from(AP_HAL::Util *util)
Definition: Util.h:27
#define f(i)
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
int get_rpi_version() const
Definition: Util_RPI.cpp:74
#define EOF
Definition: ff.h:318
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
int _check_rpi_version()
Definition: Util_RPI.cpp:31
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
char * fgets(char *str, int size, FILE *stream)
get a string from stdin See fdevopen() sets stream->put get for TTY devices
Definition: posix.c:398
int get_hw_arm32()
Definition: Util.cpp:185