mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: make AHRS attitude member variables private
This commit is contained in:
parent
caf1e33f17
commit
b3897c020e
|
@ -916,8 +916,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
pitch = ahrs.pitch;
|
pitch = ahrs.get_pitch();
|
||||||
roll = ahrs.roll;
|
roll = ahrs.get_roll();
|
||||||
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD
|
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD
|
||||||
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
|
pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD;
|
||||||
}
|
}
|
||||||
|
|
|
@ -129,9 +129,9 @@ void GCS_MAVLINK_Plane::send_attitude() const
|
||||||
{
|
{
|
||||||
const AP_AHRS &ahrs = AP::ahrs();
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
|
||||||
float r = ahrs.roll;
|
float r = ahrs.get_roll();
|
||||||
float p = ahrs.pitch;
|
float p = ahrs.get_pitch();
|
||||||
float y = ahrs.yaw;
|
float y = ahrs.get_yaw();
|
||||||
|
|
||||||
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) {
|
if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) {
|
||||||
p -= radians(plane.g.pitch_trim_cd * 0.01f);
|
p -= radians(plane.g.pitch_trim_cd * 0.01f);
|
||||||
|
|
|
@ -1090,7 +1090,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
|
||||||
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
|
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
|
||||||
|
|
||||||
// breakout when within 5 degrees of the opposite direction
|
// breakout when within 5 degrees of the opposite direction
|
||||||
if (fabsF(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) {
|
if (fabsF(wrap_PI(ahrs.get_yaw() - breakout_direction_rad)) < radians(5.0f)) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
|
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
|
||||||
vtol_approach_s.approach_stage = APPROACH_LINE;
|
vtol_approach_s.approach_stage = APPROACH_LINE;
|
||||||
set_next_WP(cmd.content.location);
|
set_next_WP(cmd.content.location);
|
||||||
|
|
|
@ -61,7 +61,7 @@ void ModeCruise::navigate()
|
||||||
|
|
||||||
// check if we are moving in the direction of the front of the vehicle
|
// check if we are moving in the direction of the front of the vehicle
|
||||||
const int32_t ground_course_cd = plane.gps.ground_course_cd();
|
const int32_t ground_course_cd = plane.gps.ground_course_cd();
|
||||||
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.yaw)) < M_PI_2;
|
const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.get_yaw())) < M_PI_2;
|
||||||
|
|
||||||
if (!locked_heading &&
|
if (!locked_heading &&
|
||||||
plane.channel_roll->get_control_in() == 0 &&
|
plane.channel_roll->get_control_in() == 0 &&
|
||||||
|
|
|
@ -52,7 +52,7 @@ void ModeGuided::update()
|
||||||
|
|
||||||
float error = 0.0f;
|
float error = 0.0f;
|
||||||
if (plane.guided_state.target_heading_type == GUIDED_HEADING_HEADING) {
|
if (plane.guided_state.target_heading_type == GUIDED_HEADING_HEADING) {
|
||||||
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().yaw);
|
error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().get_yaw());
|
||||||
} else {
|
} else {
|
||||||
Vector2f groundspeed = AP::ahrs().groundspeed_vector();
|
Vector2f groundspeed = AP::ahrs().groundspeed_vector();
|
||||||
error = wrap_PI(plane.guided_state.target_heading - atan2f(-groundspeed.y, -groundspeed.x) + M_PI);
|
error = wrap_PI(plane.guided_state.target_heading - atan2f(-groundspeed.y, -groundspeed.x) + M_PI);
|
||||||
|
|
|
@ -81,7 +81,7 @@ void ModeTakeoff::update()
|
||||||
const float dist = target_dist;
|
const float dist = target_dist;
|
||||||
if (!takeoff_started) {
|
if (!takeoff_started) {
|
||||||
const uint16_t altitude = plane.relative_ground_altitude(false,true);
|
const uint16_t altitude = plane.relative_ground_altitude(false,true);
|
||||||
const float direction = degrees(ahrs.yaw);
|
const float direction = degrees(ahrs.get_yaw());
|
||||||
// see if we will skip takeoff as already flying
|
// see if we will skip takeoff as already flying
|
||||||
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
|
if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) {
|
||||||
if (altitude >= alt) {
|
if (altitude >= alt) {
|
||||||
|
|
|
@ -2636,7 +2636,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
|
target_speed_xy_cms = diff_wp_norm * target_speed * 100;
|
||||||
target_accel_cms = diff_wp_norm * (-target_accel*100);
|
target_accel_cms = diff_wp_norm * (-target_accel*100);
|
||||||
target_yaw_deg = degrees(diff_wp_norm.angle());
|
target_yaw_deg = degrees(diff_wp_norm.angle());
|
||||||
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.yaw));
|
const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw()));
|
||||||
bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60);
|
bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60);
|
||||||
if (overshoot && !poscontrol.overshoot) {
|
if (overshoot && !poscontrol.overshoot) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
|
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f",
|
||||||
|
@ -3046,7 +3046,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
|
||||||
*/
|
*/
|
||||||
float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const
|
float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const
|
||||||
{
|
{
|
||||||
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.yaw) - target_bearing_deg));
|
const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw()) - target_bearing_deg));
|
||||||
const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
|
const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
|
||||||
if (yaw_difference > 20) {
|
if (yaw_difference > 20) {
|
||||||
// this gives a factor of 2x reduction in max speed when
|
// this gives a factor of 2x reduction in max speed when
|
||||||
|
|
Loading…
Reference in New Issue