Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: ATT.DesPitch now reports actual target, not nav output (Float version) #29067

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

Georacer
Copy link
Contributor

Alternative to #28991

It converts Plane::demanded_pitch_cd into a float, and can thus save a lot of headache: It is no longer necessary to have a second variable to track the value validity.

Still tested to work in SITL, by changing MANUAL->FBWA->MANUAL.

ArduPlane/Plane.h Outdated Show resolved Hide resolved
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There are some modes where we swap between angle controller and not. It does look like we currently just leave the angle targets hanging in those cases. Training is one case:

if (plane.training_manual_pitch) {
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pexpo);
} else {
plane.stabilize_pitch();

Nav scripting is the other:

} else if (nav_scripting_active()) {
// scripting is in control of roll and pitch rates and throttle
const float speed_scaler = get_speed_scaler();
const float aileron = rollController.get_rate_out(nav_scripting.roll_rate_dps, speed_scaler);
const float elevator = pitchController.get_rate_out(nav_scripting.pitch_rate_dps, speed_scaler);
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
float rudder = 0;
if (yawController.rate_control_enabled()) {
rudder = nav_scripting.rudder_offset_pct * 45;
if (nav_scripting.run_yaw_rate_controller) {
rudder += yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false);
} else {
yawController.reset_I();
}
}
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);

It would be nice to reflect that in the log, but it is a existing issue, so it doesn't need to be resolved here.

@@ -511,6 +511,10 @@ void Plane::update_control_mode(void)
takeoff_state.throttle_lim_max = 100.0f;
takeoff_state.throttle_lim_min = -100.0f;

// Preemptively set demanded pitch to NaN, so that it properly doesn't
// get logged. Modes ovewriting it (most modes do) will change it.
demanded_pitch = NAN;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this should be demanded_pitch_log, we need to make sure no one tries to use it for anything else. Should this be a logger.quiet_nanf()?

@@ -209,7 +209,7 @@ float Plane::stabilize_pitch_get_pitch_out()
const bool quadplane_in_frwd_transition = false;
#endif

int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
demanded_pitch = nav_pitch_cd*0.01f + g.pitch_trim + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f*g.kff_throttle_to_pitch;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this also needs setting on 196 for the quadplane case. use_fw_attitude_controllers is not quite the same as show_vtol_view that we use for switching over logging, there maybe some overlap where this would be a change in behavior.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

bump on this^

@IamPete1
Copy link
Member

I think I prefer #29152, we might as well make use of the redundant pitch logged in CTUN. It also makes it match the HUD which I think is more intuitive.

@Georacer
Copy link
Contributor Author

There are some modes where we swap between angle controller and not. It does look like we currently just leave the angle targets hanging in those cases. Training is one case [...]

Indeed the target pitch would get stuck. Now that it's being set to NaN on every loop it will be evident when it's not actually being used/followed.

@Georacer
Copy link
Contributor Author

I've updated with Peter's suggestions and tested on quadplane as well.

The top plot is the 3 pitches.
The two bottom ones are to give an indication of the plane/VTOL switch.

In FW flight the CTUN.NavPitch and ATT.DesPitch separate. In VTOL they merge back together.
I'm not sure what causes the slow merge, but I've noticed the same behaviour in master as well.

Screenshot from 2025-01-28 23-29-51

Also:
- Converted demanded_pitch_cd to float degrees.
- Initialized to NaN which will not show up in the ATT.DesPitch
plots, unless a mode (usually) overwrites it.
- Renamed demaned_pitch attribute into demanded_pitch_logged
@Georacer Georacer force-pushed the pr/log_des_pitch_float branch from e28fde0 to c7512eb Compare January 28, 2025 22:31
@tridge
Copy link
Contributor

tridge commented Jan 29, 2025

I'd like input from @Hwurzburg on this, Henry and I discussed, and Henry suggested that CTUN should have the vehicle specific trims applied, but ATT should only have the AHRS trims applied
note that CTUN for change between the fixed wing pitch trim and Q_TRIM_PITCH depending on the Q view mode

@@ -511,6 +511,10 @@ void Plane::update_control_mode(void)
takeoff_state.throttle_lim_max = 100.0f;
takeoff_state.throttle_lim_min = -100.0f;

// Preemptively set demanded pitch to NaN, so that it properly doesn't
// get logged. Modes ovewriting it (most modes do) will change it.
demanded_pitch_logged = logger.quiet_nanf();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
demanded_pitch_logged = logger.quiet_nanf();
demanded_pitch_logged = AP::logger().quiet_nanf();

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@peterbarker Why? I always assumed if we have access its better to go direct.

@Hwurzburg
Copy link
Collaborator

Hwurzburg commented Jan 29, 2025

My thoughts on Pitch logging:

  1. Any log group that reports desired/target pitch and attained/actual pitch should have both overlap when in steady state "level" flight if the vehicle has been appropriately tuned, ie in FBWA hands off mid- throttle steady state, both should be the same mean value.
  2. We should have at least one log group that shows attained/actual pitch is ZERO under steady state, level altitude, cruise conditions, ie artificial horizon level.

When we mount the autopilot,we use IMU cal to set the AHRS trims for "level AHRS". This should be in line with the fuselage line being earth frame horizontal.
We then, as desired, use PITCH_TRIM_DEG or Q_TRIM_PITCH to adjust the "flight trim" such that the artificial horizon indication in fixed wing flight is level under desired cruise conditions, or that Qplanes generally hover in place in no wind. We'll call this the level trimmed attitude.

I think that ATT pitch logs should reflect the angle departure from the level cal attitude, reflecting IMU calibration trimmed outputs (ie independent of other trimming params) and that CTUN pitch logs should reflect angle departure from level trimmed attitude (current artificial horizon level attitude indication which includes pitch trim params), whether in FW or VTOL. In both cases, the desired should match the attained pitch if steady state on a well tuned vehicle.

I think @IamPete1 agrees with me on this?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants