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: support send_extended_sys_state #19137

Merged
merged 1 commit into from Nov 8, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
24 changes: 24 additions & 0 deletions ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -1417,3 +1417,27 @@ int8_t GCS_MAVLINK_Plane::high_latency_air_temperature() const
return INT8_MIN;
}
#endif // HAL_HIGH_LATENCY2_ENABLED

MAV_VTOL_STATE GCS_MAVLINK_Plane::vtol_state() const
{
#if !HAL_QUADPLANE_ENABLED
return MAV_VTOL_STATE_UNDEFINED;
#else
if (!plane.quadplane.available()) {
return MAV_VTOL_STATE_UNDEFINED;
}

return plane.quadplane.transition->get_mav_vtol_state();
#endif
};

MAV_LANDED_STATE GCS_MAVLINK_Plane::landed_state() const
Copy link
Contributor

Choose a reason for hiding this comment

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

we could work the takeoff and landing state later

{
if (plane.is_flying()) {
// note that Q-modes almost always consider themselves as flying
return MAV_LANDED_STATE_IN_AIR;
}

return MAV_LANDED_STATE_ON_GROUND;
}

4 changes: 4 additions & 0 deletions ArduPlane/GCS_Mavlink.h
Expand Up @@ -71,4 +71,8 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK
uint8_t high_latency_wind_direction() const override;
int8_t high_latency_air_temperature() const override;
#endif // HAL_HIGH_LATENCY2_ENABLED

MAV_VTOL_STATE vtol_state() const override;
MAV_LANDED_STATE landed_state() const override;

};
24 changes: 24 additions & 0 deletions ArduPlane/quadplane.cpp
Expand Up @@ -3687,4 +3687,28 @@ bool SLT_Transition::active() const
return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER));
}

MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const
{
if (quadplane.in_vtol_mode()) {
QuadPlane::position_control_state state = quadplane.poscontrol.get_state();
if ((state == QuadPlane::position_control_state::QPOS_AIRBRAKE) || (state == QuadPlane::position_control_state::QPOS_POSITION1)) {
Copy link
Member Author

Choose a reason for hiding this comment

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

might want to limit this to only be QPOS_AIRBRAKE we can sometimes spend a while repositioning in QPOS_POSITION1

return MAV_VTOL_STATE_TRANSITION_TO_MC;
}
return MAV_VTOL_STATE_MC;
}

switch (transition_state) {
case TRANSITION_AIRSPEED_WAIT:
case TRANSITION_TIMER:
// we enter this state during assisted flight, not just
// during a forward transition.
return MAV_VTOL_STATE_TRANSITION_TO_FW;

case TRANSITION_DONE:
return MAV_VTOL_STATE_FW;
}

return MAV_VTOL_STATE_UNDEFINED;
}

#endif // HAL_QUADPLANE_ENABLED
19 changes: 19 additions & 0 deletions ArduPlane/tailsitter.cpp
Expand Up @@ -786,5 +786,24 @@ void Tailsitter_Transition::restart()
transition_initial_pitch = constrain_float(quadplane.ahrs_view->pitch_sensor,-8500,8500);
};

MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const
{
switch (transition_state) {
case TRANSITION_ANGLE_WAIT_VTOL:
return MAV_VTOL_STATE_TRANSITION_TO_MC;

case TRANSITION_DONE:
return MAV_VTOL_STATE_FW;

case TRANSITION_ANGLE_WAIT_FW: {
if (quadplane.in_vtol_mode()) {
return MAV_VTOL_STATE_MC;
}
return MAV_VTOL_STATE_TRANSITION_TO_FW;
}
}

return MAV_VTOL_STATE_UNDEFINED;
}

#endif // HAL_QUADPLANE_ENABLED
2 changes: 2 additions & 0 deletions ArduPlane/tailsitter.h
Expand Up @@ -148,6 +148,8 @@ friend class Tailsitter;

void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd, bool& allow_stick_mixing) override;

MAV_VTOL_STATE get_mav_vtol_state() const override;

private:

enum {
Expand Down
5 changes: 5 additions & 0 deletions ArduPlane/transition.h
Expand Up @@ -13,6 +13,7 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <GCS_MAVLink/GCS.h>

class QuadPlane;
class AP_MotorsMulticopter;
Expand Down Expand Up @@ -47,6 +48,8 @@ class Transition

virtual bool update_yaw_target(float& yaw_target_cd) { return false; }

virtual MAV_VTOL_STATE get_mav_vtol_state() const = 0;

protected:

// refences for convenience
Expand Down Expand Up @@ -86,6 +89,8 @@ class SLT_Transition : public Transition

bool allow_update_throttle_mix() const override;

MAV_VTOL_STATE get_mav_vtol_state() const override;

protected:

enum {
Expand Down