mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttitudeControl: add input_ prefix to input shaper functions
This commit is contained in:
parent
bba360ea2b
commit
5919e95635
@ -91,7 +91,7 @@ void AC_AttitudeControl::shift_ef_yaw_target(float yaw_shift_cd)
|
||||
_att_target_euler_rad.z = wrap_2PI(_att_target_euler_rad.z + radians(yaw_shift_cd*0.01f));
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw_smooth(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds, float smoothing_gain)
|
||||
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_smooth(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds, float smoothing_gain)
|
||||
{
|
||||
// Convert from centidegrees on public interface to radians
|
||||
float euler_roll_angle_rad = radians(euler_roll_angle_cd*0.01f);
|
||||
@ -180,7 +180,7 @@ void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw_smooth(float eule
|
||||
_ang_vel_target_rads += _att_target_ang_vel_rads;
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
|
||||
void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
|
||||
{
|
||||
// Convert from centidegrees on public interface to radians
|
||||
float euler_roll_angle_rad = radians(euler_roll_angle_cd*0.01f);
|
||||
@ -235,7 +235,7 @@ void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_
|
||||
_ang_vel_target_rads += _att_target_ang_vel_rads;
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
|
||||
void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
|
||||
{
|
||||
// Convert from centidegrees on public interface to radians
|
||||
float euler_roll_angle_rad = radians(euler_roll_angle_cd*0.01f);
|
||||
@ -274,7 +274,7 @@ void AC_AttitudeControl::euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, f
|
||||
ang_vel_to_euler_derivative(Vector3f(_ahrs.roll,_ahrs.pitch,_ahrs.yaw), _ang_vel_target_rads, _att_target_euler_deriv_rads);
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
|
||||
void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)
|
||||
{
|
||||
// Convert from centidegrees on public interface to radians
|
||||
float euler_roll_rate_rads = radians(euler_roll_rate_cds*0.01f);
|
||||
@ -331,7 +331,7 @@ void AC_AttitudeControl::euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, fl
|
||||
_ang_vel_target_rads += _att_target_ang_vel_rads;
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
|
||||
void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
|
||||
{
|
||||
// Convert from centidegrees on public interface to radians
|
||||
float roll_rate_bf_rads = radians(roll_rate_bf_cds*0.01f);
|
||||
|
@ -114,19 +114,19 @@ public:
|
||||
void shift_ef_yaw_target(float yaw_shift_cd);
|
||||
|
||||
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
|
||||
void euler_angle_roll_pitch_euler_rate_yaw_smooth(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds, float smoothing_gain);
|
||||
void input_euler_angle_roll_pitch_euler_rate_yaw_smooth(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds, float smoothing_gain);
|
||||
|
||||
// Command an euler roll and pitch angle and an euler yaw rate
|
||||
void euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds);
|
||||
void input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds);
|
||||
|
||||
// Command an euler roll, pitch and yaw angle
|
||||
void euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_ef_cd, float euler_yaw_angle_cd, bool slew_yaw);
|
||||
void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_ef_cd, float euler_yaw_angle_cd, bool slew_yaw);
|
||||
|
||||
// Command an euler roll, pitch, and yaw rate
|
||||
void euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds);
|
||||
void input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds);
|
||||
|
||||
// Command an angular velocity
|
||||
virtual void rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
|
||||
virtual void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
|
||||
|
||||
// Run angular velocity controller and send outputs to the motors
|
||||
virtual void rate_controller_run();
|
||||
|
@ -94,11 +94,11 @@ void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_pass
|
||||
}
|
||||
|
||||
// subclass non-passthrough too, for external gyro, no flybar
|
||||
void AC_AttitudeControl_Heli::rate_bf_roll_pitch_yaw(float roll_rate_bf, float pitch_rate_bf, float yaw_rate_bf)
|
||||
void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
|
||||
{
|
||||
_passthrough_yaw = yaw_rate_bf;
|
||||
_passthrough_yaw = yaw_rate_bf_cds;
|
||||
|
||||
AC_AttitudeControl::rate_bf_roll_pitch_yaw(roll_rate_bf, pitch_rate_bf, yaw_rate_bf);
|
||||
AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
|
||||
}
|
||||
|
||||
//
|
||||
|
@ -50,7 +50,7 @@ public:
|
||||
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds);
|
||||
|
||||
// subclass non-passthrough too, for external gyro, no flybar
|
||||
void rate_bf_roll_pitch_yaw(float roll_rate_bf, float pitch_rate_bf, float yaw_rate_bf) override;
|
||||
void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override;
|
||||
|
||||
// rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
|
||||
// should be called at 100hz or more
|
||||
|
Loading…
Reference in New Issue
Block a user