CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp
Views: 1798
1
// 2 or 3 structures, select one that is before target point, closest to target
2
3
/*
4
This program is free software: you can redistribute it and/or modify
5
it under the terms of the GNU General Public License as published by
6
the Free Software Foundation, either version 3 of the License, or
7
(at your option) any later version.
8
9
This program is distributed in the hope that it will be useful,
10
but WITHOUT ANY WARRANTY; without even the implied warranty of
11
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12
GNU General Public License for more details.
13
14
You should have received a copy of the GNU General Public License
15
along with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
/*
18
ArduPilot filesystem interface for system information
19
*/
20
#include "AP_Filesystem.h"
21
#include "AP_Filesystem_Sys.h"
22
23
#if AP_FILESYSTEM_SYS_ENABLED
24
25
#include <AP_Math/AP_Math.h>
26
#include <AP_CANManager/AP_CANManager.h>
27
#include <AP_Scheduler/AP_Scheduler.h>
28
#include <AP_Common/ExpandingString.h>
29
30
extern const AP_HAL::HAL& hal;
31
32
struct SysFileList {
33
const char* name;
34
};
35
36
static const SysFileList sysfs_file_list[] = {
37
{"threads.txt"},
38
{"tasks.txt"},
39
{"dma.txt"},
40
{"memory.txt"},
41
{"uarts.txt"},
42
{"timers.txt"},
43
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
44
{"can_log.txt"},
45
#endif
46
#if HAL_NUM_CAN_IFACES > 0
47
{"can0_stats.txt"},
48
{"can1_stats.txt"},
49
#endif
50
#if !defined(HAL_BOOTLOADER_BUILD) && (defined(STM32F7) || defined(STM32H7))
51
{"persistent.parm"},
52
#endif
53
{"crash_dump.bin"},
54
{"storage.bin"},
55
#if AP_FILESYSTEM_SYS_FLASH_ENABLED
56
{"flash.bin"},
57
#endif
58
};
59
60
int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) {
61
for (uint8_t i = 0; i < ARRAY_SIZE(sysfs_file_list); i++) {
62
if (strcmp(fname, sysfs_file_list[i].name) == 0) {
63
return i;
64
}
65
}
66
return -1;
67
}
68
69
int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_paths)
70
{
71
if ((flags & O_ACCMODE) != O_RDONLY) {
72
errno = EROFS;
73
return -1;
74
}
75
uint8_t idx;
76
for (idx=0; idx<max_open_file; idx++) {
77
if (!file[idx].open) {
78
break;
79
}
80
}
81
if (idx == max_open_file) {
82
errno = ENFILE;
83
return -1;
84
}
85
struct rfile &r = file[idx];
86
r.str = NEW_NOTHROW ExpandingString;
87
if (r.str == nullptr) {
88
errno = ENOMEM;
89
return -1;
90
}
91
92
// This ensure that whenever new sys file is added its also added to list above
93
int8_t pos = file_in_sysfs(fname);
94
if (pos < 0) {
95
delete r.str;
96
r.str = nullptr;
97
errno = ENOENT;
98
return -1;
99
}
100
101
if (strcmp(fname, "threads.txt") == 0) {
102
hal.util->thread_info(*r.str);
103
}
104
#if AP_SCHEDULER_ENABLED
105
if (strcmp(fname, "tasks.txt") == 0) {
106
AP::scheduler().task_info(*r.str);
107
}
108
#endif
109
if (strcmp(fname, "dma.txt") == 0) {
110
hal.util->dma_info(*r.str);
111
}
112
if (strcmp(fname, "memory.txt") == 0) {
113
hal.util->mem_info(*r.str);
114
}
115
#if HAL_UART_STATS_ENABLED
116
if (strcmp(fname, "uarts.txt") == 0) {
117
hal.util->uart_info(*r.str);
118
}
119
#endif
120
if (strcmp(fname, "timers.txt") == 0) {
121
hal.util->timer_info(*r.str);
122
}
123
#if HAL_CANMANAGER_ENABLED
124
if (strcmp(fname, "can_log.txt") == 0) {
125
AP::can().log_retrieve(*r.str);
126
}
127
#endif
128
#if HAL_NUM_CAN_IFACES > 0
129
int8_t can_stats_num = -1;
130
if (strcmp(fname, "can0_stats.txt") == 0) {
131
can_stats_num = 0;
132
} else if (strcmp(fname, "can1_stats.txt") == 0) {
133
can_stats_num = 1;
134
}
135
if (can_stats_num != -1 && can_stats_num < HAL_NUM_CAN_IFACES) {
136
if (hal.can[can_stats_num] != nullptr) {
137
hal.can[can_stats_num]->get_stats(*r.str);
138
}
139
}
140
#endif
141
if (strcmp(fname, "persistent.parm") == 0) {
142
hal.util->load_persistent_params(*r.str);
143
}
144
#if AP_CRASHDUMP_ENABLED
145
if (strcmp(fname, "crash_dump.bin") == 0) {
146
r.str->set_buffer((char*)hal.util->last_crash_dump_ptr(), hal.util->last_crash_dump_size(), hal.util->last_crash_dump_size());
147
}
148
#endif
149
if (strcmp(fname, "storage.bin") == 0) {
150
// we don't want to store the contents of storage.bin
151
// we read directly from the storage driver
152
void *ptr = nullptr;
153
size_t size = 0;
154
if (hal.storage->get_storage_ptr(ptr, size)) {
155
r.str->set_buffer((char*)ptr, size, size);
156
}
157
}
158
#if AP_FILESYSTEM_SYS_FLASH_ENABLED
159
if (strcmp(fname, "flash.bin") == 0) {
160
void *ptr = (void*)0x08000000;
161
const size_t size = BOARD_FLASH_SIZE*1024;
162
r.str->set_buffer((char*)ptr, size, size);
163
}
164
#endif
165
166
if (r.str->get_length() == 0) {
167
errno = r.str->has_failed_allocation()?ENOMEM:ENOENT;
168
delete r.str;
169
r.str = nullptr;
170
return -1;
171
}
172
r.file_ofs = 0;
173
r.open = true;
174
return idx;
175
}
176
177
int AP_Filesystem_Sys::close(int fd)
178
{
179
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
180
errno = EBADF;
181
return -1;
182
}
183
struct rfile &r = file[fd];
184
r.open = false;
185
delete r.str;
186
r.str = nullptr;
187
return 0;
188
}
189
190
int32_t AP_Filesystem_Sys::read(int fd, void *buf, uint32_t count)
191
{
192
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
193
errno = EBADF;
194
return -1;
195
}
196
struct rfile &r = file[fd];
197
count = MIN(count, r.str->get_length() - r.file_ofs);
198
memcpy(buf, &r.str->get_string()[r.file_ofs], count);
199
200
r.file_ofs += count;
201
return count;
202
}
203
204
int32_t AP_Filesystem_Sys::lseek(int fd, int32_t offset, int seek_from)
205
{
206
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
207
errno = EBADF;
208
return -1;
209
}
210
struct rfile &r = file[fd];
211
switch (seek_from) {
212
case SEEK_SET:
213
r.file_ofs = MIN(offset, int32_t(r.str->get_length()));
214
break;
215
case SEEK_CUR:
216
r.file_ofs = MIN(r.str->get_length(), offset+r.file_ofs);
217
break;
218
case SEEK_END:
219
errno = EINVAL;
220
return -1;
221
}
222
return r.file_ofs;
223
}
224
225
void *AP_Filesystem_Sys::opendir(const char *pathname)
226
{
227
if (strlen(pathname) > 0) {
228
// no sub directories
229
errno = ENOENT;
230
return nullptr;
231
}
232
DirReadTracker *dtracker = NEW_NOTHROW DirReadTracker;
233
if (dtracker == nullptr) {
234
errno = ENOMEM;
235
return nullptr;
236
}
237
return dtracker;
238
}
239
240
struct dirent *AP_Filesystem_Sys::readdir(void *dirp)
241
{
242
DirReadTracker* dtracker = ((DirReadTracker*)dirp);
243
if (dtracker->file_offset >= ARRAY_SIZE(sysfs_file_list)) {
244
// we have reached end of list
245
return nullptr;
246
}
247
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
248
dtracker->curr_file.d_type = DT_REG;
249
#endif
250
size_t max_length = ARRAY_SIZE(dtracker->curr_file.d_name);
251
strncpy_noterm(dtracker->curr_file.d_name, sysfs_file_list[dtracker->file_offset].name, max_length);
252
dtracker->file_offset++;
253
return &dtracker->curr_file;
254
}
255
256
int AP_Filesystem_Sys::closedir(void *dirp)
257
{
258
if (dirp == nullptr) {
259
errno = EINVAL;
260
return -1;
261
}
262
delete (DirReadTracker*)dirp;
263
return 0;
264
}
265
266
int AP_Filesystem_Sys::stat(const char *pathname, struct stat *stbuf)
267
{
268
if (pathname == nullptr || stbuf == nullptr || (strlen(pathname) == 0)) {
269
errno = EINVAL;
270
return -1;
271
}
272
memset(stbuf, 0, sizeof(*stbuf));
273
if (strlen(pathname) == 1 && pathname[0] == '/') {
274
stbuf->st_size = 0; // just a placeholder value
275
return 0;
276
}
277
const char *pathname_noslash = pathname;
278
if (pathname[0] == '/') {
279
pathname_noslash = &pathname[1];
280
}
281
int8_t pos = file_in_sysfs(pathname_noslash);
282
if (pos < 0) {
283
errno = ENOENT;
284
return -1;
285
}
286
// give a fixed size for stat. It is too expensive to
287
// read every file for a directory listing
288
if (strcmp(pathname_noslash, "storage.bin") == 0) {
289
stbuf->st_size = HAL_STORAGE_SIZE;
290
#if AP_CRASHDUMP_ENABLED
291
} else if (strcmp(pathname_noslash, "crash_dump.bin") == 0) {
292
stbuf->st_size = hal.util->last_crash_dump_size();
293
#endif
294
} else {
295
stbuf->st_size = 100000;
296
}
297
return 0;
298
}
299
300
#endif // AP_FILESYSTEM_SYS_ENABLED
301
302