Set up landing gear logic for tiltrotor and tailsitter VTOL. Gear is set down when in hover mode, esle gear is set up.

This commit is contained in:
Konrad 2022-03-15 09:08:08 +01:00 committed by Silvan Fuhrer
parent d7de67844f
commit e080fab8f6
2 changed files with 20 additions and 0 deletions

View File

@ -42,6 +42,8 @@
#include "tailsitter.h" #include "tailsitter.h"
#include "vtol_att_control_main.h" #include "vtol_att_control_main.h"
#include <uORB/topics/landing_gear.h>
#define PITCH_TRANSITION_FRONT_P1 -1.1f // pitch angle to switch to TRANSITION_P2 #define PITCH_TRANSITION_FRONT_P1 -1.1f // pitch angle to switch to TRANSITION_P2
#define PITCH_TRANSITION_BACK -0.25f // pitch angle to switch to MC #define PITCH_TRANSITION_BACK -0.25f // pitch angle to switch to MC
@ -361,6 +363,14 @@ void Tailsitter::fill_actuator_outputs()
_thrust_setpoint_0->xyz[2] = -mc_in[actuator_controls_s::INDEX_THROTTLE]; _thrust_setpoint_0->xyz[2] = -mc_in[actuator_controls_s::INDEX_THROTTLE];
} }
// Landing Gear
if (_vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = landing_gear_s::GEAR_DOWN;
} else {
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = landing_gear_s::GEAR_UP;
}
if (_params->elevons_mc_lock && _vtol_schedule.flight_mode == vtol_mode::MC_MODE) { if (_params->elevons_mc_lock && _vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
fw_out[actuator_controls_s::INDEX_ROLL] = 0; fw_out[actuator_controls_s::INDEX_ROLL] = 0;
fw_out[actuator_controls_s::INDEX_PITCH] = 0; fw_out[actuator_controls_s::INDEX_PITCH] = 0;

View File

@ -42,6 +42,8 @@
#include "tiltrotor.h" #include "tiltrotor.h"
#include "vtol_att_control_main.h" #include "vtol_att_control_main.h"
#include <uORB/topics/landing_gear.h>
using namespace matrix; using namespace matrix;
using namespace time_literals; using namespace time_literals;
@ -520,6 +522,14 @@ void Tiltrotor::fill_actuator_outputs()
_thrust_setpoint_0->xyz[0] = -_thrust_setpoint_0->xyz[2] * sinf(_tilt_control * M_PI_2_F); _thrust_setpoint_0->xyz[0] = -_thrust_setpoint_0->xyz[2] * sinf(_tilt_control * M_PI_2_F);
} }
// Landing gear
if (_vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = landing_gear_s::GEAR_DOWN;
} else {
mc_out[actuator_controls_s::INDEX_LANDING_GEAR] = landing_gear_s::GEAR_UP;
}
// Fixed wing output // Fixed wing output
fw_out[4] = _tilt_control; fw_out[4] = _tilt_control;