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/Tools/Replay/Replay.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "Replay.h"
17
18
#include "LogReader.h"
19
20
#include <stdio.h>
21
#include <AP_HAL/utility/getopt_cpp.h>
22
23
#include <AP_Vehicle/AP_Vehicle.h>
24
25
#include <GCS_MAVLink/GCS_Dummy.h>
26
#include <AP_Filesystem/AP_Filesystem.h>
27
#include <AP_Filesystem/posix_compat.h>
28
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
29
30
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
31
#include <AP_HAL_Linux/Scheduler.h>
32
#endif
33
34
#define streq(x, y) (!strcmp(x, y))
35
36
static ReplayVehicle replayvehicle;
37
38
// list of user parameters
39
user_parameter *user_parameters;
40
bool replay_force_ekf2;
41
bool replay_force_ekf3;
42
43
const AP_Param::Info ReplayVehicle::var_info[] = {
44
GSCALAR(dummy, "_DUMMY", 0),
45
46
// @Group: BARO
47
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
48
GOBJECT(barometer, "BARO", AP_Baro),
49
50
// @Group: INS
51
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
52
GOBJECT(ins, "INS", AP_InertialSensor),
53
54
// @Group: AHRS_
55
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
56
GOBJECT(ahrs, "AHRS_", AP_AHRS),
57
58
#if AP_AIRSPEED_ENABLED
59
// @Group: ARSPD_
60
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
61
GOBJECT(airspeed, "ARSP_", AP_Airspeed),
62
#endif
63
64
// @Group: EK2_
65
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
66
GOBJECTN(ekf2, NavEKF2, "EK2_", NavEKF2),
67
68
// @Group: COMPASS_
69
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
70
GOBJECT(compass, "COMPASS_", Compass),
71
72
// @Group: EK3_
73
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
74
GOBJECTN(ekf3, NavEKF3, "EK3_", NavEKF3),
75
76
// @Group: GPS
77
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
78
GOBJECT(gps, "GPS", AP_GPS),
79
80
AP_VAREND
81
};
82
83
void ReplayVehicle::load_parameters(void)
84
{
85
AP_Param::check_var_info();
86
87
StorageManager::erase();
88
AP_Param::erase_all();
89
// Load all auto-loaded EEPROM variables - also registers thread
90
// which saves parameters, which Compass now does in its init() routine
91
AP_Param::load_all();
92
}
93
94
const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
95
AP_GROUPEND
96
};
97
GCS_Dummy _gcs;
98
99
#if AP_ADVANCEDFAILSAFE_ENABLED
100
AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }
101
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }
102
#endif
103
104
// dummy method to avoid linking AP_Avoidance
105
// AP_Avoidance *AP::ap_avoidance() { return nullptr; }
106
107
#if AP_LTM_TELEM_ENABLED
108
// avoid building/linking LTM:
109
void AP_LTM_Telem::init() {};
110
#endif
111
#if AP_DEVO_TELEM_ENABLED
112
// avoid building/linking Devo:
113
void AP_DEVO_Telem::init() {};
114
#endif
115
116
void ReplayVehicle::init_ardupilot(void)
117
{
118
// we pass an empty log structure, filling the structure in with
119
// either the format present in the log (if we do not emit the
120
// message as a product of Replay), or the format understood in
121
// the current code (if we do emit the message in the normal
122
// places in the EKF, for example)
123
logger.set_force_log_disarmed(true);
124
}
125
126
void Replay::usage(void)
127
{
128
::printf("Options:\n");
129
::printf("\t--parm NAME=VALUE set parameter NAME to VALUE\n");
130
::printf("\t--param-file FILENAME load parameters from a file\n");
131
::printf("\t--force-ekf2 force enable EKF2\n");
132
::printf("\t--force-ekf3 force enable EKF3\n");
133
}
134
135
enum param_key : uint8_t {
136
FORCE_EKF2 = 1,
137
FORCE_EKF3,
138
};
139
140
void Replay::_parse_command_line(uint8_t argc, char * const argv[])
141
{
142
const struct GetOptLong::option options[] = {
143
// name has_arg flag val
144
{"parm", true, 0, 'p'},
145
{"param", true, 0, 'p'},
146
{"param-file", true, 0, 'F'},
147
{"force-ekf2", false, 0, param_key::FORCE_EKF2},
148
{"force-ekf3", false, 0, param_key::FORCE_EKF3},
149
{"help", false, 0, 'h'},
150
{0, false, 0, 0}
151
};
152
153
GetOptLong gopt(argc, argv, "p:F:h", options);
154
155
int opt;
156
while ((opt = gopt.getoption()) != -1) {
157
switch (opt) {
158
case 'p': {
159
const char *eq = strchr(gopt.optarg, '=');
160
if (eq == NULL) {
161
::printf("Usage: -p NAME=VALUE\n");
162
exit(1);
163
}
164
struct user_parameter *u = NEW_NOTHROW user_parameter;
165
strncpy(u->name, gopt.optarg, eq-gopt.optarg);
166
u->value = atof(eq+1);
167
u->next = user_parameters;
168
user_parameters = u;
169
break;
170
}
171
172
case 'F':
173
load_param_file(gopt.optarg);
174
break;
175
176
case param_key::FORCE_EKF2:
177
replay_force_ekf2 = true;
178
break;
179
180
case param_key::FORCE_EKF3:
181
replay_force_ekf3 = true;
182
break;
183
184
case 'h':
185
default:
186
usage();
187
exit(0);
188
}
189
}
190
191
argv += gopt.optind;
192
argc -= gopt.optind;
193
194
if (argc > 0) {
195
filename = argv[0];
196
}
197
}
198
199
void Replay::setup()
200
{
201
::printf("Starting\n");
202
203
uint8_t argc;
204
char * const *argv;
205
206
hal.util->commandline_arguments(argc, argv);
207
208
if (argc > 0) {
209
_parse_command_line(argc, argv);
210
}
211
212
_vehicle.setup();
213
214
set_user_parameters();
215
216
if (replay_force_ekf2) {
217
reader.set_parameter("EK2_ENABLE", 1, true);
218
}
219
if (replay_force_ekf3) {
220
reader.set_parameter("EK3_ENABLE", 1, true);
221
}
222
223
if (replay_force_ekf2 && replay_force_ekf3) {
224
::printf("Cannot force both EKF types\n");
225
exit(1);
226
}
227
228
if (filename == nullptr) {
229
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
230
// allow replay on stm32
231
filename = "APM/replayin.bin";
232
#else
233
::printf("You must supply a log filename\n");
234
exit(1);
235
#endif
236
}
237
// LogReader reader = LogReader(log_structure);
238
if (!reader.open_log(filename)) {
239
::printf("open(%s): %m\n", filename);
240
exit(1);
241
}
242
}
243
244
void Replay::loop()
245
{
246
if (!reader.update()) {
247
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
248
// If we don't tear down the threads then they continue to access
249
// global state during object destruction.
250
((Linux::Scheduler*)hal.scheduler)->teardown();
251
#endif
252
exit(0);
253
}
254
}
255
256
/*
257
setup user -p parameters
258
*/
259
void Replay::set_user_parameters(void)
260
{
261
for (struct user_parameter *u=user_parameters; u; u=u->next) {
262
if (!reader.set_parameter(u->name, u->value, true)) {
263
::printf("Failed to set parameter %s to %f\n", u->name, u->value);
264
exit(1);
265
}
266
}
267
}
268
269
/*
270
parse a parameter file line
271
*/
272
bool Replay::parse_param_line(char *line, char **vname, float &value)
273
{
274
if (line[0] == '#') {
275
return false;
276
}
277
char *saveptr = NULL;
278
char *pname = strtok_r(line, ", =\t", &saveptr);
279
if (pname == NULL) {
280
return false;
281
}
282
if (strlen(pname) > AP_MAX_NAME_SIZE) {
283
return false;
284
}
285
const char *value_s = strtok_r(NULL, ", =\t", &saveptr);
286
if (value_s == NULL) {
287
return false;
288
}
289
value = atof(value_s);
290
*vname = pname;
291
return true;
292
}
293
294
295
/*
296
load a default set of parameters from a file
297
*/
298
void Replay::load_param_file(const char *pfilename)
299
{
300
auto &fs = AP::FS();
301
int fd = fs.open(pfilename, O_RDONLY, true);
302
if (fd == -1) {
303
printf("Failed to open parameter file: %s\n", pfilename);
304
exit(1);
305
}
306
char line[100];
307
308
while (fs.fgets(line, sizeof(line)-1, fd)) {
309
char *pname;
310
float value;
311
if (!parse_param_line(line, &pname, value)) {
312
continue;
313
}
314
struct user_parameter *u = NEW_NOTHROW user_parameter;
315
strncpy_noterm(u->name, pname, sizeof(u->name));
316
u->value = value;
317
u->next = user_parameters;
318
user_parameters = u;
319
}
320
fs.close(fd);
321
}
322
323
Replay replay(replayvehicle);
324
AP_Vehicle& vehicle = replayvehicle;
325
326
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
327
328
AP_HAL_MAIN_CALLBACKS(&replay);
329
330