mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ADC: updates for AP_HAL::MemberProc
This commit is contained in:
parent
2095b2a2d7
commit
d83dbb38b4
@ -171,7 +171,7 @@ void AP_ADC_ADS7844::Init()
|
|||||||
|
|
||||||
_ch6_last_sample_time_micros = hal.scheduler->micros();
|
_ch6_last_sample_time_micros = hal.scheduler->micros();
|
||||||
|
|
||||||
hal.scheduler->register_timer_process( reinterpret_cast<AP_HAL::TimedProc>(&AP_ADC_ADS7844::read), this );
|
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_ADC_ADS7844::read));
|
||||||
hal.scheduler->resume_timer_procs();
|
hal.scheduler->resume_timer_procs();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -49,7 +49,7 @@ AP_ADC_HIL::AP_ADC_HIL()
|
|||||||
|
|
||||||
void AP_ADC_HIL::Init()
|
void AP_ADC_HIL::Init()
|
||||||
{
|
{
|
||||||
hal.scheduler->register_timer_process( reinterpret_cast<AP_HAL::TimedProc>(&AP_ADC_HIL::read), this);
|
hal.scheduler->register_timer_process( AP_HAL_MEMBERPROC(&AP_ADC_HIL::read));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read one channel value
|
// Read one channel value
|
||||||
|
Loading…
Reference in New Issue
Block a user