mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Plane: Quadplane: tailsitter only change view once transision is complete
This commit is contained in:
parent
b61cf72b8c
commit
f972d3dc2f
@ -123,7 +123,7 @@ void GCS_MAVLINK_Plane::send_attitude() const
|
|||||||
float p = ahrs.pitch - radians(plane.g.pitch_trim_cd*0.01f);
|
float p = ahrs.pitch - radians(plane.g.pitch_trim_cd*0.01f);
|
||||||
float y = ahrs.yaw;
|
float y = ahrs.yaw;
|
||||||
|
|
||||||
if (plane.quadplane.in_vtol_mode()) {
|
if (plane.quadplane.show_vtol_view()) {
|
||||||
r = plane.quadplane.ahrs_view->roll;
|
r = plane.quadplane.ahrs_view->roll;
|
||||||
p = plane.quadplane.ahrs_view->pitch;
|
p = plane.quadplane.ahrs_view->pitch;
|
||||||
y = plane.quadplane.ahrs_view->yaw;
|
y = plane.quadplane.ahrs_view->yaw;
|
||||||
|
@ -17,7 +17,7 @@ void Plane::Log_Write_Attitude(void)
|
|||||||
targets.z = 0;
|
targets.z = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (quadplane.tailsitter_active() || quadplane.in_vtol_mode()) {
|
if (quadplane.show_vtol_view()) {
|
||||||
// we need the attitude targets from the AC_AttitudeControl controller, as they
|
// we need the attitude targets from the AC_AttitudeControl controller, as they
|
||||||
// account for the acceleration limits.
|
// account for the acceleration limits.
|
||||||
// Also, for bodyframe roll input types, _attitude_target_euler_angle is not maintained
|
// Also, for bodyframe roll input types, _attitude_target_euler_angle is not maintained
|
||||||
|
@ -3380,3 +3380,23 @@ bool QuadPlane::in_vtol_land_sequence(void) const
|
|||||||
{
|
{
|
||||||
return in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final();
|
return in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return true if we should show VTOL view
|
||||||
|
bool QuadPlane::show_vtol_view() const
|
||||||
|
{
|
||||||
|
bool show_vtol = in_vtol_mode();
|
||||||
|
|
||||||
|
if (is_tailsitter() && hal.util->get_soft_armed()) {
|
||||||
|
if (show_vtol && (transition_state == TRANSITION_ANGLE_WAIT_VTOL)) {
|
||||||
|
// in a vtol mode but still transitioning from forward flight
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!show_vtol && (transition_state == TRANSITION_ANGLE_WAIT_FW)) {
|
||||||
|
// not in VTOL mode but still transitioning from VTOL
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return show_vtol;
|
||||||
|
}
|
||||||
|
@ -95,6 +95,7 @@ public:
|
|||||||
bool in_vtol_mode(void) const;
|
bool in_vtol_mode(void) const;
|
||||||
bool in_vtol_posvel_mode(void) const;
|
bool in_vtol_posvel_mode(void) const;
|
||||||
void update_throttle_hover();
|
void update_throttle_hover();
|
||||||
|
bool show_vtol_view() const;
|
||||||
|
|
||||||
// vtol help for is_flying()
|
// vtol help for is_flying()
|
||||||
bool is_flying(void);
|
bool is_flying(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user