mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
DataFlash: Remove redundant state from MAVLink backend
This commit is contained in:
parent
bce10f48af
commit
d819690426
@ -50,10 +50,6 @@ void DataFlash_MAVLink::Init()
|
||||
stats_init();
|
||||
|
||||
_initialised = true;
|
||||
_logging_started = true; // in actual fact, we throw away
|
||||
// everything until a client connects.
|
||||
// This stops calls to start_new_log from
|
||||
// the vehicles
|
||||
}
|
||||
|
||||
bool DataFlash_MAVLink::logging_failed() const
|
||||
@ -356,7 +352,7 @@ void DataFlash_MAVLink::Log_Write_DF_MAV(DataFlash_MAVLink &df)
|
||||
|
||||
void DataFlash_MAVLink::stats_log()
|
||||
{
|
||||
if (!_initialised || !_logging_started) {
|
||||
if (!_initialised) {
|
||||
return;
|
||||
}
|
||||
if (stats.collection_count == 0) {
|
||||
@ -401,7 +397,7 @@ uint8_t DataFlash_MAVLink::queue_size(dm_block_queue_t queue)
|
||||
|
||||
void DataFlash_MAVLink::stats_collect()
|
||||
{
|
||||
if (!_initialised || !_logging_started) {
|
||||
if (!_initialised) {
|
||||
return;
|
||||
}
|
||||
if (!semaphore->take_nonblocking()) {
|
||||
@ -476,7 +472,7 @@ bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue)
|
||||
|
||||
void DataFlash_MAVLink::push_log_blocks()
|
||||
{
|
||||
if (!_initialised || !_logging_started ||!_sending_to_client) {
|
||||
if (!_initialised || !_sending_to_client) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -500,7 +496,7 @@ void DataFlash_MAVLink::push_log_blocks()
|
||||
|
||||
void DataFlash_MAVLink::do_resends(uint32_t now)
|
||||
{
|
||||
if (!_initialised || !_logging_started ||!_sending_to_client) {
|
||||
if (!_initialised || !_sending_to_client) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -33,7 +33,9 @@ public:
|
||||
// initialisation
|
||||
void Init() override;
|
||||
|
||||
bool logging_started() const override { return _logging_started; }
|
||||
// in actual fact, we throw away everything until a client connects.
|
||||
// This stops calls to start_new_log from the vehicles
|
||||
bool logging_started() const override { return _initialised; }
|
||||
|
||||
void stop_logging() override;
|
||||
|
||||
@ -137,7 +139,6 @@ private:
|
||||
|
||||
uint32_t _next_seq_num;
|
||||
uint16_t _latest_block_len;
|
||||
bool _logging_started;
|
||||
uint32_t _last_response_time;
|
||||
uint32_t _last_send_time;
|
||||
uint8_t _next_block_number_to_resend;
|
||||
|
Loading…
Reference in New Issue
Block a user