mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 08:04:14 -03:00
AP_Scheduler: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
efffed0510
commit
806bc4898b
@ -256,7 +256,7 @@ void AP_Scheduler::run(uint32_t time_available)
|
||||
/*
|
||||
return number of micros until the current task reaches its deadline
|
||||
*/
|
||||
uint16_t AP_Scheduler::time_available_usec(void)
|
||||
uint16_t AP_Scheduler::time_available_usec(void) const
|
||||
{
|
||||
uint32_t dt = AP_HAL::micros() - _task_time_started;
|
||||
if (dt > _task_time_allowed) {
|
||||
|
@ -108,7 +108,7 @@ public:
|
||||
void run(uint32_t time_available);
|
||||
|
||||
// return the number of microseconds available for the current task
|
||||
uint16_t time_available_usec(void);
|
||||
uint16_t time_available_usec(void) const;
|
||||
|
||||
// return debug parameter
|
||||
uint8_t debug_flags(void) { return _debug; }
|
||||
|
@ -160,7 +160,7 @@ float AP::PerfInfo::get_filtered_time() const
|
||||
return filtered_loop_time;
|
||||
}
|
||||
|
||||
void AP::PerfInfo::update_logging()
|
||||
void AP::PerfInfo::update_logging() const
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_WARNING,
|
||||
"PERF: %u/%u [%lu:%lu] F=%uHz sd=%lu Ex=%lu",
|
||||
|
@ -34,7 +34,7 @@ public:
|
||||
float get_filtered_time() const;
|
||||
void set_loop_rate(uint16_t rate_hz);
|
||||
|
||||
void update_logging();
|
||||
void update_logging() const;
|
||||
|
||||
// allocate the array of task statistics for use by @SYS/tasks.txt
|
||||
void allocate_task_info(uint8_t num_tasks);
|
||||
|
Loading…
Reference in New Issue
Block a user