AP_Mount: make AHRS attitude member variables private

This commit is contained in:
Peter Barker 2024-01-12 23:40:23 +11:00 committed by Peter Barker
parent 71a00dc733
commit 49c697221a
5 changed files with 11 additions and 11 deletions

View File

@ -413,7 +413,7 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli
void AP_Mount_Backend::write_log(uint64_t timestamp_us)
{
// return immediately if no yaw estimate
float ahrs_yaw = AP::ahrs().yaw;
float ahrs_yaw = AP::ahrs().get_yaw();
if (isnan(ahrs_yaw)) {
return;
}
@ -734,7 +734,7 @@ float AP_Mount_Backend::MountTarget::get_bf_yaw() const
{
if (yaw_is_ef) {
// convert to body-frame
return wrap_PI(yaw - AP::ahrs().yaw);
return wrap_PI(yaw - AP::ahrs().get_yaw());
}
// target is already body-frame
@ -750,7 +750,7 @@ float AP_Mount_Backend::MountTarget::get_ef_yaw() const
}
// convert to earth-frame
return wrap_PI(yaw + AP::ahrs().yaw);
return wrap_PI(yaw + AP::ahrs().get_yaw());
}
// sets roll, pitch, yaw and yaw_is_ef

View File

@ -160,7 +160,7 @@ void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad)
}
// retrieve lean angles from ahrs
Vector2f ahrs_angle_rad = {ahrs.roll, ahrs.pitch};
Vector2f ahrs_angle_rad = {ahrs.get_roll(), ahrs.get_pitch()};
// rotate ahrs roll and pitch angles to gimbal yaw
if (has_pan_control()) {
@ -174,7 +174,7 @@ void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad)
// lead filter
const Vector3f &gyro = ahrs.get_gyro();
if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.pitch) < M_PI/3.0f) {
if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.get_pitch()) < M_PI/3.0f) {
// Compute rate of change of euler roll angle
float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll());
_angle_bf_output_rad.x -= roll_rate * _params.roll_stb_lead;

View File

@ -709,7 +709,7 @@ void AP_Mount_Siyi::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_
const float pitch_rate_scalar = constrain_float(100.0 * pitch_err_rad * AP_MOUNT_SIYI_PITCH_P / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100);
// convert yaw angle to body-frame
float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad;
float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad;
// enforce body-frame yaw angle limits. If beyond limits always use body-frame control
const float yaw_bf_min = radians(_params.yaw_angle_min);
@ -1127,9 +1127,9 @@ void AP_Mount_Siyi::send_attitude(void)
const uint32_t now_ms = AP_HAL::millis();
attitude.time_boot_ms = now_ms;
attitude.roll = ahrs.roll;
attitude.pitch = ahrs.pitch;
attitude.yaw = ahrs.yaw;
attitude.roll = ahrs.get_roll();
attitude.pitch = ahrs.get_pitch();
attitude.yaw = ahrs.get_yaw();
attitude.rollspeed = gyro.x;
attitude.pitchspeed = gyro.y;
attitude.yawspeed = gyro.z;

View File

@ -544,7 +544,7 @@ bool AP_Mount_Viewpro::send_target_angles(float pitch_rad, float yaw_rad, bool y
}
// convert yaw angle to body-frame
float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad;
float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad;
// enforce body-frame yaw angle limits. If beyond limits always use body-frame control
const float yaw_bf_min = radians(_params.yaw_angle_min);

View File

@ -379,7 +379,7 @@ void AP_Mount_Xacti::send_target_rates(float pitch_rads, float yaw_rads, bool ya
void AP_Mount_Xacti::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef)
{
// convert yaw to body frame
const float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad;
const float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad;
// send angle target to gimbal
send_gimbal_control(2, degrees(pitch_rad) * 100, degrees(yaw_bf_rad) * 100);