Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/Replay/Replay.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "Replay.h"1617#include "LogReader.h"1819#include <stdio.h>20#include <AP_HAL/utility/getopt_cpp.h>2122#include <AP_Vehicle/AP_Vehicle.h>2324#include <GCS_MAVLink/GCS_Dummy.h>25#include <AP_Filesystem/AP_Filesystem.h>26#include <AP_Filesystem/posix_compat.h>27#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>2829#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX30#include <AP_HAL_Linux/Scheduler.h>31#endif3233#define streq(x, y) (!strcmp(x, y))3435static ReplayVehicle replayvehicle;3637// list of user parameters38user_parameter *user_parameters;39bool replay_force_ekf2;40bool replay_force_ekf3;4142const AP_Param::Info ReplayVehicle::var_info[] = {43GSCALAR(dummy, "_DUMMY", 0),4445// @Group: BARO46// @Path: ../libraries/AP_Baro/AP_Baro.cpp47GOBJECT(barometer, "BARO", AP_Baro),4849// @Group: INS50// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp51GOBJECT(ins, "INS", AP_InertialSensor),5253// @Group: AHRS_54// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp55GOBJECT(ahrs, "AHRS_", AP_AHRS),5657#if AP_AIRSPEED_ENABLED58// @Group: ARSPD_59// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp60GOBJECT(airspeed, "ARSP_", AP_Airspeed),61#endif6263// @Group: EK2_64// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp65GOBJECTN(ekf2, NavEKF2, "EK2_", NavEKF2),6667// @Group: COMPASS_68// @Path: ../libraries/AP_Compass/AP_Compass.cpp69GOBJECT(compass, "COMPASS_", Compass),7071// @Group: EK3_72// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp73GOBJECTN(ekf3, NavEKF3, "EK3_", NavEKF3),7475// @Group: GPS76// @Path: ../libraries/AP_GPS/AP_GPS.cpp77GOBJECT(gps, "GPS", AP_GPS),7879AP_VAREND80};8182void ReplayVehicle::load_parameters(void)83{84AP_Param::check_var_info();8586StorageManager::erase();87AP_Param::erase_all();88// Load all auto-loaded EEPROM variables - also registers thread89// which saves parameters, which Compass now does in its init() routine90AP_Param::load_all();91}9293const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {94AP_GROUPEND95};96GCS_Dummy _gcs;9798#if AP_ADVANCEDFAILSAFE_ENABLED99AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }100bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) { return false; }101#endif102103// dummy method to avoid linking AP_Avoidance104// AP_Avoidance *AP::ap_avoidance() { return nullptr; }105106#if AP_LTM_TELEM_ENABLED107// avoid building/linking LTM:108void AP_LTM_Telem::init() {};109#endif110#if AP_DEVO_TELEM_ENABLED111// avoid building/linking Devo:112void AP_DEVO_Telem::init() {};113#endif114115void ReplayVehicle::init_ardupilot(void)116{117// we pass an empty log structure, filling the structure in with118// either the format present in the log (if we do not emit the119// message as a product of Replay), or the format understood in120// the current code (if we do emit the message in the normal121// places in the EKF, for example)122logger.set_force_log_disarmed(true);123}124125void Replay::usage(void)126{127::printf("Options:\n");128::printf("\t--parm NAME=VALUE set parameter NAME to VALUE\n");129::printf("\t--param-file FILENAME load parameters from a file\n");130::printf("\t--force-ekf2 force enable EKF2\n");131::printf("\t--force-ekf3 force enable EKF3\n");132}133134enum param_key : uint8_t {135FORCE_EKF2 = 1,136FORCE_EKF3,137};138139void Replay::_parse_command_line(uint8_t argc, char * const argv[])140{141const struct GetOptLong::option options[] = {142// name has_arg flag val143{"parm", true, 0, 'p'},144{"param", true, 0, 'p'},145{"param-file", true, 0, 'F'},146{"force-ekf2", false, 0, param_key::FORCE_EKF2},147{"force-ekf3", false, 0, param_key::FORCE_EKF3},148{"help", false, 0, 'h'},149{0, false, 0, 0}150};151152GetOptLong gopt(argc, argv, "p:F:h", options);153154int opt;155while ((opt = gopt.getoption()) != -1) {156switch (opt) {157case 'p': {158const char *eq = strchr(gopt.optarg, '=');159if (eq == NULL) {160::printf("Usage: -p NAME=VALUE\n");161exit(1);162}163struct user_parameter *u = NEW_NOTHROW user_parameter;164strncpy(u->name, gopt.optarg, eq-gopt.optarg);165u->value = atof(eq+1);166u->next = user_parameters;167user_parameters = u;168break;169}170171case 'F':172load_param_file(gopt.optarg);173break;174175case param_key::FORCE_EKF2:176replay_force_ekf2 = true;177break;178179case param_key::FORCE_EKF3:180replay_force_ekf3 = true;181break;182183case 'h':184default:185usage();186exit(0);187}188}189190argv += gopt.optind;191argc -= gopt.optind;192193if (argc > 0) {194filename = argv[0];195}196}197198void Replay::setup()199{200::printf("Starting\n");201202uint8_t argc;203char * const *argv;204205hal.util->commandline_arguments(argc, argv);206207if (argc > 0) {208_parse_command_line(argc, argv);209}210211_vehicle.setup();212213set_user_parameters();214215if (replay_force_ekf2) {216reader.set_parameter("EK2_ENABLE", 1, true);217}218if (replay_force_ekf3) {219reader.set_parameter("EK3_ENABLE", 1, true);220}221222if (replay_force_ekf2 && replay_force_ekf3) {223::printf("Cannot force both EKF types\n");224exit(1);225}226227if (filename == nullptr) {228#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS229// allow replay on stm32230filename = "APM/replayin.bin";231#else232::printf("You must supply a log filename\n");233exit(1);234#endif235}236// LogReader reader = LogReader(log_structure);237if (!reader.open_log(filename)) {238::printf("open(%s): %m\n", filename);239exit(1);240}241}242243void Replay::loop()244{245if (!reader.update()) {246#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX247// If we don't tear down the threads then they continue to access248// global state during object destruction.249((Linux::Scheduler*)hal.scheduler)->teardown();250#endif251exit(0);252}253}254255/*256setup user -p parameters257*/258void Replay::set_user_parameters(void)259{260for (struct user_parameter *u=user_parameters; u; u=u->next) {261if (!reader.set_parameter(u->name, u->value, true)) {262::printf("Failed to set parameter %s to %f\n", u->name, u->value);263exit(1);264}265}266}267268/*269parse a parameter file line270*/271bool Replay::parse_param_line(char *line, char **vname, float &value)272{273if (line[0] == '#') {274return false;275}276char *saveptr = NULL;277char *pname = strtok_r(line, ", =\t", &saveptr);278if (pname == NULL) {279return false;280}281if (strlen(pname) > AP_MAX_NAME_SIZE) {282return false;283}284const char *value_s = strtok_r(NULL, ", =\t", &saveptr);285if (value_s == NULL) {286return false;287}288value = atof(value_s);289*vname = pname;290return true;291}292293294/*295load a default set of parameters from a file296*/297void Replay::load_param_file(const char *pfilename)298{299auto &fs = AP::FS();300int fd = fs.open(pfilename, O_RDONLY, true);301if (fd == -1) {302printf("Failed to open parameter file: %s\n", pfilename);303exit(1);304}305char line[100];306307while (fs.fgets(line, sizeof(line)-1, fd)) {308char *pname;309float value;310if (!parse_param_line(line, &pname, value)) {311continue;312}313struct user_parameter *u = NEW_NOTHROW user_parameter;314strncpy_noterm(u->name, pname, sizeof(u->name));315u->value = value;316u->next = user_parameters;317user_parameters = u;318}319fs.close(fd);320}321322Replay replay(replayvehicle);323AP_Vehicle& vehicle = replayvehicle;324325const AP_HAL::HAL& hal = AP_HAL::get_HAL();326327AP_HAL_MAIN_CALLBACKS(&replay);328329330