AC_AttControl: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:05:22 +09:00 committed by Randy Mackay
parent 071d8e541e
commit ea08b6115d

View File

@ -310,14 +310,14 @@ void AC_PosControl::init_takeoff()
// is_active_z - returns true if the z-axis position controller has been run very recently
bool AC_PosControl::is_active_z() const
{
return ((hal.scheduler->millis() - _last_update_z_ms) <= POSCONTROL_ACTIVE_TIMEOUT_MS);
return ((AP_HAL::millis() - _last_update_z_ms) <= POSCONTROL_ACTIVE_TIMEOUT_MS);
}
/// update_z_controller - fly to altitude in cm above home
void AC_PosControl::update_z_controller()
{
// check time since last cast
uint32_t now = hal.scheduler->millis();
uint32_t now = AP_HAL::millis();
if (now - _last_update_z_ms > POSCONTROL_ACTIVE_TIMEOUT_MS) {
_flags.reset_rate_to_accel_z = true;
_flags.reset_accel_to_throttle = true;
@ -612,7 +612,7 @@ float AC_PosControl::get_distance_to_target() const
// is_active_xy - returns true if the xy position controller has been run very recently
bool AC_PosControl::is_active_xy() const
{
return ((hal.scheduler->millis() - _last_update_xy_ms) <= POSCONTROL_ACTIVE_TIMEOUT_MS);
return ((AP_HAL::millis() - _last_update_xy_ms) <= POSCONTROL_ACTIVE_TIMEOUT_MS);
}
/// init_xy_controller - initialise the xy controller
@ -642,7 +642,7 @@ void AC_PosControl::init_xy_controller(bool reset_I)
void AC_PosControl::update_xy_controller(xy_mode mode, float ekfNavVelGainScaler, bool use_althold_lean_angle)
{
// compute dt
uint32_t now = hal.scheduler->millis();
uint32_t now = AP_HAL::millis();
float dt = (now - _last_update_xy_ms) / 1000.0f;
_last_update_xy_ms = now;
@ -669,7 +669,7 @@ void AC_PosControl::update_xy_controller(xy_mode mode, float ekfNavVelGainScaler
float AC_PosControl::time_since_last_xy_update() const
{
uint32_t now = hal.scheduler->millis();
uint32_t now = AP_HAL::millis();
return (now - _last_update_xy_ms)*0.001f;
}
@ -706,7 +706,7 @@ void AC_PosControl::init_vel_controller_xyz()
void AC_PosControl::update_vel_controller_xyz(float ekfNavVelGainScaler)
{
// capture time since last iteration
uint32_t now = hal.scheduler->millis();
uint32_t now = AP_HAL::millis();
float dt = (now - _last_update_xy_ms)*0.001f;
// call xy controller