Browse Source

DataFlash: Delete unused arguments.

master
murata 7 years ago committed by Randy Mackay
parent
commit
396517fe58
  1. 8
      libraries/DataFlash/DataFlash_Backend.cpp
  2. 4
      libraries/DataFlash/DataFlash_Backend.h
  3. 4
      libraries/DataFlash/DataFlash_File.cpp
  4. 4
      libraries/DataFlash/DataFlash_File.h
  5. 4
      libraries/DataFlash/DataFlash_File_sd.cpp
  6. 4
      libraries/DataFlash/DataFlash_File_sd.h
  7. 4
      libraries/DataFlash/DataFlash_MAVLink.cpp
  8. 4
      libraries/DataFlash/DataFlash_MAVLink.h

8
libraries/DataFlash/DataFlash_Backend.cpp

@ -49,10 +49,10 @@ DataFlash_Backend::vehicle_startup_message_Log_Writer DataFlash_Backend::vehicle @@ -49,10 +49,10 @@ DataFlash_Backend::vehicle_startup_message_Log_Writer DataFlash_Backend::vehicle
void DataFlash_Backend::periodic_10Hz(const uint32_t now)
{
}
void DataFlash_Backend::periodic_1Hz(const uint32_t now)
void DataFlash_Backend::periodic_1Hz()
{
}
void DataFlash_Backend::periodic_fullrate(const uint32_t now)
void DataFlash_Backend::periodic_fullrate()
{
}
@ -60,14 +60,14 @@ void DataFlash_Backend::periodic_tasks() @@ -60,14 +60,14 @@ void DataFlash_Backend::periodic_tasks()
{
uint32_t now = AP_HAL::millis();
if (now - _last_periodic_1Hz > 1000) {
periodic_1Hz(now);
periodic_1Hz();
_last_periodic_1Hz = now;
}
if (now - _last_periodic_10Hz > 100) {
periodic_10Hz(now);
_last_periodic_10Hz = now;
}
periodic_fullrate(now);
periodic_fullrate();
}
void DataFlash_Backend::start_new_log_reset_variables()

4
libraries/DataFlash/DataFlash_Backend.h

@ -131,8 +131,8 @@ protected: @@ -131,8 +131,8 @@ protected:
DataFlash_Class &_front;
virtual void periodic_10Hz(const uint32_t now);
virtual void periodic_1Hz(const uint32_t now);
virtual void periodic_fullrate(const uint32_t now);
virtual void periodic_1Hz();
virtual void periodic_fullrate();
bool ShouldLog(bool is_critical);
virtual bool WritesOK() const = 0;

4
libraries/DataFlash/DataFlash_File.cpp

@ -183,7 +183,7 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const @@ -183,7 +183,7 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
return ret;
}
void DataFlash_File::periodic_1Hz(const uint32_t now)
void DataFlash_File::periodic_1Hz()
{
if (!io_thread_alive()) {
if (io_thread_warning_decimation_counter == 0) {
@ -204,7 +204,7 @@ void DataFlash_File::periodic_1Hz(const uint32_t now) @@ -204,7 +204,7 @@ void DataFlash_File::periodic_1Hz(const uint32_t now)
df_stats_log();
}
void DataFlash_File::periodic_fullrate(const uint32_t now)
void DataFlash_File::periodic_fullrate()
{
DataFlash_Backend::push_log_blocks();
}

4
libraries/DataFlash/DataFlash_File.h

@ -45,8 +45,8 @@ public: @@ -45,8 +45,8 @@ public:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
void flush(void) override;
#endif
void periodic_1Hz(const uint32_t now) override;
void periodic_fullrate(const uint32_t now) override;
void periodic_1Hz() override;
void periodic_fullrate() override;
// this method is used when reporting system status over mavlink
bool logging_enabled() const override;

4
libraries/DataFlash/DataFlash_File_sd.cpp

@ -131,7 +131,7 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const @@ -131,7 +131,7 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
return ret;
}
void DataFlash_File::periodic_1Hz(const uint32_t now)
void DataFlash_File::periodic_1Hz()
{
if (!(_write_fd) || !_initialised || _open_error || _busy) return; // too early
@ -148,7 +148,7 @@ void DataFlash_File::periodic_1Hz(const uint32_t now) @@ -148,7 +148,7 @@ void DataFlash_File::periodic_1Hz(const uint32_t now)
}
}
void DataFlash_File::periodic_fullrate(const uint32_t now)
void DataFlash_File::periodic_fullrate()
{
DataFlash_Backend::push_log_blocks();
}

4
libraries/DataFlash/DataFlash_File_sd.h

@ -46,8 +46,8 @@ public: @@ -46,8 +46,8 @@ public:
uint16_t get_num_logs() override;
uint16_t start_new_log(void) override;
void periodic_1Hz(const uint32_t now) override;
void periodic_fullrate(const uint32_t now);
void periodic_1Hz() override;
void periodic_fullrate();
// this method is used when reporting system status over mavlink
bool logging_enabled() const;

4
libraries/DataFlash/DataFlash_MAVLink.cpp

@ -532,7 +532,7 @@ void DataFlash_MAVLink::periodic_10Hz(const uint32_t now) @@ -532,7 +532,7 @@ void DataFlash_MAVLink::periodic_10Hz(const uint32_t now)
do_resends(now);
stats_collect();
}
void DataFlash_MAVLink::periodic_1Hz(const uint32_t now)
void DataFlash_MAVLink::periodic_1Hz()
{
if (_sending_to_client &&
_last_response_time + 10000 < _last_send_time) {
@ -544,7 +544,7 @@ void DataFlash_MAVLink::periodic_1Hz(const uint32_t now) @@ -544,7 +544,7 @@ void DataFlash_MAVLink::periodic_1Hz(const uint32_t now)
stats_log();
}
void DataFlash_MAVLink::periodic_fullrate(uint32_t now)
void DataFlash_MAVLink::periodic_fullrate()
{
push_log_blocks();
}

4
libraries/DataFlash/DataFlash_MAVLink.h

@ -156,8 +156,8 @@ private: @@ -156,8 +156,8 @@ private:
struct dm_block *next_block();
void periodic_10Hz(uint32_t now) override;
void periodic_1Hz(uint32_t now) override;
void periodic_fullrate(uint32_t now) override;
void periodic_1Hz() override;
void periodic_fullrate() override;
void stats_init();
void stats_reset();

Loading…
Cancel
Save