mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_Logger: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
41c653f973
commit
18d8f19801
@ -1114,7 +1114,7 @@ AP_Logger::log_write_fmt *AP_Logger::msg_fmt_for_name(const char *name, const ch
|
|||||||
return f;
|
return f;
|
||||||
}
|
}
|
||||||
|
|
||||||
const struct LogStructure *AP_Logger::structure_for_msg_type(const uint8_t msg_type)
|
const struct LogStructure *AP_Logger::structure_for_msg_type(const uint8_t msg_type) const
|
||||||
{
|
{
|
||||||
for (uint16_t i=0; i<_num_types;i++) {
|
for (uint16_t i=0; i<_num_types;i++) {
|
||||||
const struct LogStructure *s = structure(i);
|
const struct LogStructure *s = structure(i);
|
||||||
|
@ -497,7 +497,7 @@ private:
|
|||||||
// return (possibly allocating) a log_write_fmt for a name
|
// return (possibly allocating) a log_write_fmt for a name
|
||||||
const struct log_write_fmt *log_write_fmt_for_msg_type(uint8_t msg_type) const;
|
const struct log_write_fmt *log_write_fmt_for_msg_type(uint8_t msg_type) const;
|
||||||
|
|
||||||
const struct LogStructure *structure_for_msg_type(uint8_t msg_type);
|
const struct LogStructure *structure_for_msg_type(uint8_t msg_type) const;
|
||||||
|
|
||||||
// return a msg_type which is not currently in use (or -1 if none available)
|
// return a msg_type which is not currently in use (or -1 if none available)
|
||||||
int16_t find_free_msg_type() const;
|
int16_t find_free_msg_type() const;
|
||||||
@ -588,7 +588,7 @@ private:
|
|||||||
// can be used by other subsystems to detect if they should log data
|
// can be used by other subsystems to detect if they should log data
|
||||||
uint8_t _log_start_count;
|
uint8_t _log_start_count;
|
||||||
|
|
||||||
bool should_handle_log_message();
|
bool should_handle_log_message() const;
|
||||||
void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
||||||
|
|
||||||
void handle_log_request_list(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
void handle_log_request_list(class GCS_MAVLINK &, const mavlink_message_t &msg);
|
||||||
|
@ -44,7 +44,7 @@ const struct MultiplierStructure *AP_Logger_Backend::multiplier(uint8_t num) con
|
|||||||
return _front.multiplier(num);
|
return _front.multiplier(num);
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_message_writer() {
|
AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_message_writer() const {
|
||||||
return _front._vehicle_messages;
|
return _front._vehicle_messages;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -15,7 +15,7 @@ public:
|
|||||||
AP_Logger_Backend(AP_Logger &front,
|
AP_Logger_Backend(AP_Logger &front,
|
||||||
class LoggerMessageWriter_DFLogStart *writer);
|
class LoggerMessageWriter_DFLogStart *writer);
|
||||||
|
|
||||||
vehicle_startup_message_Writer vehicle_message_writer();
|
vehicle_startup_message_Writer vehicle_message_writer() const;
|
||||||
|
|
||||||
virtual bool CardInserted(void) const = 0;
|
virtual bool CardInserted(void) const = 0;
|
||||||
|
|
||||||
|
@ -261,7 +261,7 @@ void AP_Logger_Block::StartLogFile(uint16_t FileNumber)
|
|||||||
df_Write_FilePage = 1;
|
df_Write_FilePage = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t AP_Logger_Block::GetFileNumber()
|
uint16_t AP_Logger_Block::GetFileNumber() const
|
||||||
{
|
{
|
||||||
return df_FileNumber;
|
return df_FileNumber;
|
||||||
}
|
}
|
||||||
|
@ -41,12 +41,12 @@ protected:
|
|||||||
bool WritesOK() const override;
|
bool WritesOK() const override;
|
||||||
|
|
||||||
// get the current sector from the current page
|
// get the current sector from the current page
|
||||||
uint32_t get_sector(uint32_t current_page) {
|
uint32_t get_sector(uint32_t current_page) const {
|
||||||
return ((current_page - 1) / df_PagePerSector);
|
return ((current_page - 1) / df_PagePerSector);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get the current block from the current page
|
// get the current block from the current page
|
||||||
uint32_t get_block(uint32_t current_page) {
|
uint32_t get_block(uint32_t current_page) const {
|
||||||
return ((current_page - 1) / df_PagePerBlock);
|
return ((current_page - 1) / df_PagePerBlock);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -154,7 +154,7 @@ private:
|
|||||||
|
|
||||||
void StartLogFile(uint16_t FileNumber);
|
void StartLogFile(uint16_t FileNumber);
|
||||||
// file numbers
|
// file numbers
|
||||||
uint16_t GetFileNumber();
|
uint16_t GetFileNumber() const;
|
||||||
|
|
||||||
void _print_log_formats(AP_HAL::BetterStream *port);
|
void _print_log_formats(AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
|
@ -54,7 +54,7 @@ uint32_t AP_Logger_MAVLink::bufferspace_available() {
|
|||||||
return (_blockcount_free * 200 + remaining_space_in_current_block());
|
return (_blockcount_free * 200 + remaining_space_in_current_block());
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t AP_Logger_MAVLink::remaining_space_in_current_block() {
|
uint8_t AP_Logger_MAVLink::remaining_space_in_current_block() const {
|
||||||
// note that _current_block *could* be NULL ATM.
|
// note that _current_block *could* be NULL ATM.
|
||||||
return (MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN - _latest_block_len);
|
return (MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN - _latest_block_len);
|
||||||
}
|
}
|
||||||
|
@ -145,7 +145,7 @@ private:
|
|||||||
void Write_logger_MAV(AP_Logger_MAVLink &logger);
|
void Write_logger_MAV(AP_Logger_MAVLink &logger);
|
||||||
|
|
||||||
uint32_t bufferspace_available() override; // in bytes
|
uint32_t bufferspace_available() override; // in bytes
|
||||||
uint8_t remaining_space_in_current_block();
|
uint8_t remaining_space_in_current_block() const;
|
||||||
// write buffer
|
// write buffer
|
||||||
uint8_t _blockcount_free;
|
uint8_t _blockcount_free;
|
||||||
uint8_t _blockcount;
|
uint8_t _blockcount;
|
||||||
|
@ -25,7 +25,7 @@
|
|||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// We avoid doing log messages when timing is critical:
|
// We avoid doing log messages when timing is critical:
|
||||||
bool AP_Logger::should_handle_log_message()
|
bool AP_Logger::should_handle_log_message() const
|
||||||
{
|
{
|
||||||
if (!WritesEnabled()) {
|
if (!WritesEnabled()) {
|
||||||
// this is currently used as a proxy for "in_mavlink_delay"
|
// this is currently used as a proxy for "in_mavlink_delay"
|
||||||
|
@ -92,8 +92,8 @@ public:
|
|||||||
|
|
||||||
void reset() override;
|
void reset() override;
|
||||||
void process() override;
|
void process() override;
|
||||||
bool fmt_done() { return _fmt_done; }
|
bool fmt_done() const { return _fmt_done; }
|
||||||
bool params_done() { return _params_done; }
|
bool params_done() const { return _params_done; }
|
||||||
|
|
||||||
// reset some writers so we push stuff out to logs again. Will
|
// reset some writers so we push stuff out to logs again. Will
|
||||||
// only work if we are in state DONE!
|
// only work if we are in state DONE!
|
||||||
|
Loading…
Reference in New Issue
Block a user