Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/Replay/Replay.h
9660 views
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 <AP_Vehicle/AP_Vehicle.h>
17
#include <AP_Vehicle/AP_FixedWing.h>
18
#include <SRV_Channel/SRV_Channel.h>
19
#include <AP_Arming/AP_Arming.h>
20
21
#include "LogReader.h"
22
23
#define AP_PARAM_VEHICLE_NAME replayvehicle
24
25
struct user_parameter {
26
struct user_parameter *next;
27
char name[17];
28
float value;
29
};
30
31
extern user_parameter *user_parameters;
32
extern bool replay_force_ekf2;
33
extern bool replay_force_ekf3;
34
35
class ReplayVehicle : public AP_Vehicle {
36
public:
37
friend class Replay;
38
39
ReplayVehicle() { unused_log_bitmask.set(-1); }
40
// HAL::Callbacks implementation.
41
void load_parameters(void) override;
42
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
43
uint8_t &task_count,
44
uint32_t &log_bit) override {
45
tasks = nullptr;
46
task_count = 0;
47
log_bit = 0;
48
};
49
50
virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; }
51
virtual uint8_t get_mode() const override { return 0; }
52
53
AP_FixedWing aparm;
54
55
AP_Int32 unused_log_bitmask; // logging is magic for Replay; this is unused
56
struct LogStructure log_structure[256] = {
57
};
58
59
NavEKF2 ekf2;
60
NavEKF3 ekf3;
61
62
SRV_Channels servo_channels;
63
64
AP_Arming arming;
65
66
protected:
67
68
const AP_Int32 &get_log_bitmask() override { return unused_log_bitmask; }
69
const struct LogStructure *get_log_structures() const override {
70
return log_structure;
71
}
72
uint8_t get_num_log_structures() const override {
73
return uint8_t(ARRAY_SIZE(log_structure));
74
}
75
76
void init_ardupilot() override;
77
78
private:
79
Parameters g;
80
81
// setup the var_info table
82
AP_Param param_loader{var_info};
83
84
static const AP_Param::Info var_info[];
85
};
86
87
class Replay : public AP_HAL::HAL::Callbacks {
88
89
public:
90
Replay(ReplayVehicle &vehicle) :
91
_vehicle(vehicle) { }
92
93
void setup() override;
94
void loop() override;
95
96
// return true if a user parameter of name is set
97
bool check_user_param(const char *name);
98
99
private:
100
const char *filename;
101
ReplayVehicle &_vehicle;
102
103
LogReader reader{_vehicle.log_structure, _vehicle.ekf2, _vehicle.ekf3};
104
bool show_progress = false; // Flag to determine if progress bar should be shown
105
uint32_t last_progress_update = 0; // Last time progress was displayed
106
107
void _parse_command_line(uint8_t argc, char * const argv[]);
108
109
void set_user_parameters(void);
110
bool parse_param_line(char *line, char **vname, float &value);
111
void load_param_file(const char *filename);
112
void usage();
113
114
void Write_Format(const struct LogStructure &s);
115
void write_EKF_formats(void);
116
};
117
118