Skip to content

Commit

Permalink
Plane:adjust CTUN.Pitch to remove PITCH_TRIM
Browse files Browse the repository at this point in the history
fix
  • Loading branch information
Hwurzburg committed Jan 28, 2025
1 parent 4e12b4e commit 35b7417
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,13 +102,19 @@ void Plane::Log_Write_Control_Tuning()
synthetic_airspeed = logger.quiet_nan();
}

int16_t pitch = ahrs.pitch_sensor - g.pitch_trim * 100.0f;
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
pitch = ahrs.pitch_sensor;
}
#endif
struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
time_us : AP_HAL::micros64(),
nav_roll_cd : (int16_t)nav_roll_cd,
roll : (int16_t)ahrs.roll_sensor,
nav_pitch_cd : (int16_t)nav_pitch_cd,
pitch : (int16_t)ahrs.pitch_sensor,
pitch : pitch,
throttle_out : SRV_Channels::get_output_scaled(SRV_Channel::k_throttle),
rudder_out : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder),
throttle_dem : TECS_controller.get_throttle_demand(),
Expand Down

0 comments on commit 35b7417

Please sign in to comment.