mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Logger: remove time_us parameter to several sensor logging methods
These were used by the old Replay code to try to provide a frame of sensor data by correlating the timestamps. That Replay code has been removed.
This commit is contained in:
parent
e257dd9fee
commit
d50e4d03f4
@ -229,7 +229,7 @@ public:
|
||||
void Write_Event(LogEvent id);
|
||||
void Write_Error(LogErrorSubsystem sub_system,
|
||||
LogErrorCode error_code);
|
||||
void Write_GPS(uint8_t instance, uint64_t time_us=0);
|
||||
void Write_GPS(uint8_t instance);
|
||||
void Write_IMU();
|
||||
bool Write_ISBH(uint16_t seqno,
|
||||
AP_InertialSensor::IMU_SENSOR_TYPE sensor_type,
|
||||
@ -248,7 +248,7 @@ public:
|
||||
void Write_RCOUT(void);
|
||||
void Write_RSSI();
|
||||
void Write_Rally();
|
||||
void Write_Baro(uint64_t time_us=0);
|
||||
void Write_Baro();
|
||||
void Write_Power(void);
|
||||
void Write_AHRS2();
|
||||
void Write_POS();
|
||||
@ -264,7 +264,7 @@ public:
|
||||
void Write_Attitude(const Vector3f &targets);
|
||||
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Write_Current();
|
||||
void Write_Compass(uint64_t time_us=0);
|
||||
void Write_Compass();
|
||||
void Write_Mode(uint8_t mode, const ModeReason reason);
|
||||
|
||||
void Write_EntireMission();
|
||||
|
@ -131,12 +131,10 @@ bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap,
|
||||
}
|
||||
|
||||
// Write an GPS packet
|
||||
void AP_Logger::Write_GPS(uint8_t i, uint64_t time_us)
|
||||
void AP_Logger::Write_GPS(uint8_t i)
|
||||
{
|
||||
const AP_GPS &gps = AP::gps();
|
||||
if (time_us == 0) {
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const uint64_t time_us = AP_HAL::micros64();
|
||||
const struct Location &loc = gps.location(i);
|
||||
|
||||
float yaw_deg=0, yaw_accuracy_deg=0;
|
||||
@ -290,11 +288,9 @@ void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance)
|
||||
}
|
||||
|
||||
// Write a BARO packet
|
||||
void AP_Logger::Write_Baro(uint64_t time_us)
|
||||
void AP_Logger::Write_Baro()
|
||||
{
|
||||
if (time_us == 0) {
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const uint64_t time_us = AP_HAL::micros64();
|
||||
const AP_Baro &baro = AP::baro();
|
||||
for (uint8_t i=0; i< baro.num_instances(); i++) {
|
||||
Write_Baro_instance(time_us, i);
|
||||
@ -330,7 +326,7 @@ void AP_Logger::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_ins
|
||||
// Write an raw accel/gyro data packet
|
||||
void AP_Logger::Write_IMU()
|
||||
{
|
||||
uint64_t time_us = AP_HAL::micros64();
|
||||
const uint64_t time_us = AP_HAL::micros64();
|
||||
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
|
||||
@ -692,11 +688,9 @@ void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag
|
||||
}
|
||||
|
||||
// Write a Compass packet
|
||||
void AP_Logger::Write_Compass(uint64_t time_us)
|
||||
void AP_Logger::Write_Compass()
|
||||
{
|
||||
if (time_us == 0) {
|
||||
time_us = AP_HAL::micros64();
|
||||
}
|
||||
const uint64_t time_us = AP_HAL::micros64();
|
||||
const Compass &compass = AP::compass();
|
||||
for (uint8_t i=0; i<compass.get_count(); i++) {
|
||||
Write_Compass_instance(time_us, i);
|
||||
|
Loading…
Reference in New Issue
Block a user