mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_Linux: Simplification of the code
I applied the ArduPilot coding style guide and additionally simplified the code where possible.
This commit is contained in:
parent
1fc4063117
commit
15a915edd3
@ -99,6 +99,7 @@ float AnalogIn_Navio2::board_voltage(void)
|
||||
{
|
||||
return _board_voltage_pin->voltage_average();
|
||||
}
|
||||
|
||||
float AnalogIn_Navio2::servorail_voltage(void)
|
||||
{
|
||||
return _servorail_pin->voltage_average();
|
||||
|
@ -99,8 +99,9 @@ bool Util::is_chardev_node(const char *path)
|
||||
{
|
||||
struct stat st;
|
||||
|
||||
if (!path || lstat(path, &st) < 0)
|
||||
if (!path || lstat(path, &st) < 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return S_ISCHR(st.st_mode);
|
||||
}
|
||||
@ -120,7 +121,7 @@ int Util::write_file(const char *path, const char *fmt, ...)
|
||||
{
|
||||
errno = 0;
|
||||
|
||||
int fd = ::open(path, O_WRONLY | O_CLOEXEC);
|
||||
int fd = open(path, O_WRONLY | O_CLOEXEC);
|
||||
if (fd == -1) {
|
||||
return -errno;
|
||||
}
|
||||
@ -128,9 +129,9 @@ int Util::write_file(const char *path, const char *fmt, ...)
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
|
||||
int ret = ::vdprintf(fd, fmt, args);
|
||||
int ret = vdprintf(fd, fmt, args);
|
||||
int errno_bkp = errno;
|
||||
::close(fd);
|
||||
close(fd);
|
||||
|
||||
va_end(args);
|
||||
|
||||
@ -145,21 +146,23 @@ int Util::read_file(const char *path, const char *fmt, ...)
|
||||
{
|
||||
errno = 0;
|
||||
|
||||
FILE *file = ::fopen(path, "re");
|
||||
if (!file)
|
||||
FILE *file = fopen(path, "re");
|
||||
if (!file) {
|
||||
return -errno;
|
||||
}
|
||||
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
|
||||
int ret = ::vfscanf(file, fmt, args);
|
||||
int ret = vfscanf(file, fmt, args);
|
||||
int errno_bkp = errno;
|
||||
::fclose(file);
|
||||
fclose(file);
|
||||
|
||||
va_end(args);
|
||||
|
||||
if (ret < 1)
|
||||
if (ret < 1) {
|
||||
return -errno_bkp;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -174,33 +177,25 @@ const char *Linux::Util::_hw_names[UTIL_NUM_HARDWARES] = {
|
||||
#define MAX_SIZE_LINE 50
|
||||
int Util::get_hw_arm32()
|
||||
{
|
||||
int ret = -ENOENT;
|
||||
char buffer[MAX_SIZE_LINE];
|
||||
const char* hardware_description_entry = "Hardware";
|
||||
char* flag;
|
||||
FILE* f;
|
||||
|
||||
f = fopen("/proc/cpuinfo", "r");
|
||||
|
||||
char buffer[MAX_SIZE_LINE] = { 0 };
|
||||
FILE *f = fopen("/proc/cpuinfo", "r");
|
||||
if (f == NULL) {
|
||||
ret = -errno;
|
||||
goto end;
|
||||
return -errno;
|
||||
}
|
||||
|
||||
while (fgets(buffer, MAX_SIZE_LINE, f) != NULL) {
|
||||
flag = strstr(buffer, hardware_description_entry);
|
||||
if (flag != NULL) {
|
||||
if (strstr(buffer, "Hardware") == NULL) {
|
||||
continue;
|
||||
}
|
||||
for (uint8_t i = 0; i < UTIL_NUM_HARDWARES; i++) {
|
||||
if (strstr(buffer, _hw_names[i]) != 0) {
|
||||
ret = i;
|
||||
goto close_end;
|
||||
}
|
||||
if (strstr(buffer, _hw_names[i]) == NULL) {
|
||||
continue;
|
||||
}
|
||||
fclose(f);
|
||||
return i;
|
||||
}
|
||||
}
|
||||
|
||||
close_end:
|
||||
fclose(f);
|
||||
end:
|
||||
return ret;
|
||||
return -ENOENT;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user