Tools: Replay: use baro singleton
This commit is contained in:
parent
06f6135daa
commit
3a718366e1
@ -105,7 +105,7 @@ void LR_MsgHandler_BARO::process_message(uint8_t *msg)
|
||||
if (!field_value(msg, "SMS", last_update_ms)) {
|
||||
last_update_ms = 0;
|
||||
}
|
||||
baro.setHIL(0,
|
||||
AP::baro().setHIL(0,
|
||||
require_field_float(msg, "Press"),
|
||||
require_field_int16_t(msg, "Temp") * 0.01f,
|
||||
require_field_float(msg, "Alt"),
|
||||
|
@ -113,13 +113,12 @@ class LR_MsgHandler_BARO : public LR_MsgHandler
|
||||
{
|
||||
public:
|
||||
LR_MsgHandler_BARO(log_Format &_f, DataFlash_Class &_dataflash,
|
||||
uint64_t &_last_timestamp_usec, AP_Baro &_baro)
|
||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec), baro(_baro) { };
|
||||
uint64_t &_last_timestamp_usec)
|
||||
: LR_MsgHandler(_f, _dataflash, _last_timestamp_usec)
|
||||
{ };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
|
||||
private:
|
||||
AP_Baro &baro;
|
||||
};
|
||||
|
||||
|
||||
|
@ -39,13 +39,12 @@ const struct LogStructure log_structure[] = {
|
||||
"FBBBGGB000"}
|
||||
};
|
||||
|
||||
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps,
|
||||
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass, AP_GPS &_gps,
|
||||
AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const char **&_nottypes):
|
||||
DataFlashFileReader(),
|
||||
vehicle(VehicleType::VEHICLE_UNKNOWN),
|
||||
ahrs(_ahrs),
|
||||
ins(_ins),
|
||||
baro(_baro),
|
||||
compass(_compass),
|
||||
gps(_gps),
|
||||
airspeed(_airspeed),
|
||||
@ -231,7 +230,7 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
|
||||
sim_attitude);
|
||||
} else if (streq(name, "BARO")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_BARO(formats[f.type], dataflash,
|
||||
last_timestamp_usec, baro);
|
||||
last_timestamp_usec);
|
||||
} else if (streq(name, "ARM")) {
|
||||
msgparser[f.type] = new LR_MsgHandler_ARM(formats[f.type], dataflash,
|
||||
last_timestamp_usec);
|
||||
|
@ -6,7 +6,7 @@
|
||||
class LogReader : public DataFlashFileReader
|
||||
{
|
||||
public:
|
||||
LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const char **¬types);
|
||||
LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const char **¬types);
|
||||
bool wait_type(const char *type);
|
||||
|
||||
const Vector3f &get_attitude(void) const { return attitude; }
|
||||
@ -37,7 +37,6 @@ protected:
|
||||
private:
|
||||
AP_AHRS &ahrs;
|
||||
AP_InertialSensor &ins;
|
||||
AP_Baro &baro;
|
||||
Compass &compass;
|
||||
AP_GPS &gps;
|
||||
AP_Airspeed &airspeed;
|
||||
|
@ -64,9 +64,9 @@ public:
|
||||
Compass compass;
|
||||
AP_SerialManager serial_manager;
|
||||
RangeFinder rng{serial_manager, ROTATION_PITCH_270};
|
||||
NavEKF2 EKF2{&ahrs, barometer, rng};
|
||||
NavEKF3 EKF3{&ahrs, barometer, rng};
|
||||
AP_AHRS_NavEKF ahrs{ins, barometer, EKF2, EKF3};
|
||||
NavEKF2 EKF2{&ahrs, rng};
|
||||
NavEKF3 EKF3{&ahrs, rng};
|
||||
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3};
|
||||
AP_InertialNav_NavEKF inertial_nav{ahrs};
|
||||
AP_Vehicle::FixedWing aparm;
|
||||
AP_Airspeed airspeed;
|
||||
@ -121,7 +121,7 @@ private:
|
||||
SITL::SITL sitl;
|
||||
#endif
|
||||
|
||||
LogReader logreader{_vehicle.ahrs, _vehicle.ins, _vehicle.barometer, _vehicle.compass, _vehicle.gps, _vehicle.airspeed, _vehicle.dataflash, nottypes};
|
||||
LogReader logreader{_vehicle.ahrs, _vehicle.ins, _vehicle.compass, _vehicle.gps, _vehicle.airspeed, _vehicle.dataflash, nottypes};
|
||||
|
||||
FILE *ekf1f;
|
||||
FILE *ekf2f;
|
||||
|
Loading…
Reference in New Issue
Block a user