Skip to content

Commit

Permalink
Plane: log quadplane transision state
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Sep 30, 2020
1 parent f972d3d commit 6621b69
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 1 deletion.
3 changes: 2 additions & 1 deletion ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,8 +375,9 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: CRt: climb rate
// @Field: TMix: transition throttle mix value
// @Field: Sscl: speed scalar for tailsitter control surfaces
// @Field: Trans: Transistion state
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
"QTUN", "Qffffffeccff", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl", "s----mmmnn--", "F----00000-0" },
"QTUN", "QffffffeccffB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trans", "s----mmmnn---", "F----00000-0-" },

// @LoggerMessage: AOA
// @Description: Angle of attack and Side Slip Angle values
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2941,6 +2941,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
climb_rate : int16_t(inertial_nav.get_velocity_z()),
throttle_mix : attitude_control->get_throttle_mix(),
speed_scaler : last_spd_scaler,
transition_state : static_cast<uint8_t>(transition_state)
};
plane.logger.WriteBlock(&pkt, sizeof(pkt));

Expand Down
1 change: 1 addition & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ class QuadPlane
int16_t climb_rate;
float throttle_mix;
float speed_scaler;
uint8_t transition_state;
};

MAV_TYPE get_mav_type(void) const;
Expand Down

0 comments on commit 6621b69

Please sign in to comment.