mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Plane: support send_extended_sys_state
This commit is contained in:
parent
e95aedd748
commit
7c3de472b2
@ -1417,3 +1417,27 @@ int8_t GCS_MAVLINK_Plane::high_latency_air_temperature() const
|
|||||||
return INT8_MIN;
|
return INT8_MIN;
|
||||||
}
|
}
|
||||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
#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
|
||||||
|
{
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
|
@ -71,4 +71,8 @@ private:
|
|||||||
uint8_t high_latency_wind_direction() const override;
|
uint8_t high_latency_wind_direction() const override;
|
||||||
int8_t high_latency_air_temperature() const override;
|
int8_t high_latency_air_temperature() const override;
|
||||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||||
|
|
||||||
|
MAV_VTOL_STATE vtol_state() const override;
|
||||||
|
MAV_LANDED_STATE landed_state() const override;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -3692,4 +3692,28 @@ bool SLT_Transition::active() const
|
|||||||
return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER));
|
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)) {
|
||||||
|
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
|
#endif // HAL_QUADPLANE_ENABLED
|
||||||
|
@ -786,5 +786,24 @@ void Tailsitter_Transition::restart()
|
|||||||
transition_initial_pitch = constrain_float(quadplane.ahrs_view->pitch_sensor,-8500,8500);
|
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
|
#endif // HAL_QUADPLANE_ENABLED
|
||||||
|
@ -148,6 +148,8 @@ public:
|
|||||||
|
|
||||||
void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd, bool& allow_stick_mixing) override;
|
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:
|
private:
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
|
@ -13,6 +13,7 @@
|
|||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
class QuadPlane;
|
class QuadPlane;
|
||||||
class AP_MotorsMulticopter;
|
class AP_MotorsMulticopter;
|
||||||
@ -47,6 +48,8 @@ public:
|
|||||||
|
|
||||||
virtual bool update_yaw_target(float& yaw_target_cd) { return false; }
|
virtual bool update_yaw_target(float& yaw_target_cd) { return false; }
|
||||||
|
|
||||||
|
virtual MAV_VTOL_STATE get_mav_vtol_state() const = 0;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// refences for convenience
|
// refences for convenience
|
||||||
@ -86,6 +89,8 @@ public:
|
|||||||
|
|
||||||
bool allow_update_throttle_mix() const override;
|
bool allow_update_throttle_mix() const override;
|
||||||
|
|
||||||
|
MAV_VTOL_STATE get_mav_vtol_state() const override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
|
Loading…
Reference in New Issue
Block a user