mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: rate_controller_run_dt() takes dt as last argument
This commit is contained in:
parent
15de449d12
commit
eeda86ccb4
|
@ -245,7 +245,7 @@ public:
|
||||||
virtual void rate_controller_target_reset() {}
|
virtual void rate_controller_target_reset() {}
|
||||||
|
|
||||||
// optional variant to allow running with different dt
|
// optional variant to allow running with different dt
|
||||||
virtual void rate_controller_run_dt(float dt, const Vector3f& gyro) { AP_BoardConfig::config_error("rate_controller_run_dt() must be defined"); };
|
virtual void rate_controller_run_dt(const Vector3f& gyro, float dt) { AP_BoardConfig::config_error("rate_controller_run_dt() must be defined"); };
|
||||||
|
|
||||||
// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
|
// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
|
||||||
void euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads);
|
void euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads);
|
||||||
|
|
|
@ -439,7 +439,7 @@ void AC_AttitudeControl_Multi::update_throttle_rpy_mix()
|
||||||
_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);
|
_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AC_AttitudeControl_Multi::rate_controller_run_dt(float dt, const Vector3f& gyro)
|
void AC_AttitudeControl_Multi::rate_controller_run_dt(const Vector3f& gyro, float dt)
|
||||||
{
|
{
|
||||||
// take a copy of the target so that it can't be changed from under us.
|
// take a copy of the target so that it can't be changed from under us.
|
||||||
Vector3f ang_vel_body = _ang_vel_body;
|
Vector3f ang_vel_body = _ang_vel_body;
|
||||||
|
@ -481,7 +481,7 @@ void AC_AttitudeControl_Multi::rate_controller_target_reset()
|
||||||
void AC_AttitudeControl_Multi::rate_controller_run()
|
void AC_AttitudeControl_Multi::rate_controller_run()
|
||||||
{
|
{
|
||||||
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
Vector3f gyro_latest = _ahrs.get_gyro_latest();
|
||||||
rate_controller_run_dt(_dt, gyro_latest);
|
rate_controller_run_dt(gyro_latest, _dt);
|
||||||
}
|
}
|
||||||
|
|
||||||
// sanity check parameters. should be called once before takeoff
|
// sanity check parameters. should be called once before takeoff
|
||||||
|
|
|
@ -76,7 +76,7 @@ public:
|
||||||
bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f * _thr_mix_min); }
|
bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f * _thr_mix_min); }
|
||||||
|
|
||||||
// run lowest level body-frame rate controller and send outputs to the motors
|
// run lowest level body-frame rate controller and send outputs to the motors
|
||||||
void rate_controller_run_dt(float dt, const Vector3f& gyro) override;
|
void rate_controller_run_dt(const Vector3f& gyro, float dt) override;
|
||||||
void rate_controller_target_reset() override;
|
void rate_controller_target_reset() override;
|
||||||
void rate_controller_run() override;
|
void rate_controller_run() override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue