PX4 Firmware
PX4 Autopilot Software http://px4.io
Tailsitter Class Reference

#include <tailsitter.h>

Inheritance diagram for Tailsitter:
Collaboration diagram for Tailsitter:

Public Member Functions

 Tailsitter (VtolAttitudeControl *_att_controller)
 
 ~Tailsitter () override=default
 
void update_vtol_state () override
 Update vtol state. More...
 
void update_transition_state () override
 Update transition state. More...
 
void update_fw_state () override
 Update fixed wing state. More...
 
void fill_actuator_outputs () override
 Write data to actuator output topic. More...
 
void waiting_on_tecs () override
 Special handling opportunity for the time right after transition to FW before TECS is running. More...
 
- Public Member Functions inherited from VtolType
 VtolType (VtolAttitudeControl *att_controller)
 
 VtolType (const VtolType &)=delete
 
VtolTypeoperator= (const VtolType &)=delete
 
virtual ~VtolType ()=default
 
bool init ()
 Initialise. More...
 
virtual void update_mc_state ()
 Update multicopter state. More...
 
void check_quadchute_condition ()
 Checks for fixed-wing failsafe condition and issues abort request if needed. More...
 
bool can_transition_on_ground ()
 Returns true if we're allowed to do a mode transition on the ground. More...
 
mode get_mode ()
 

Private Types

enum  vtol_mode { vtol_mode::MC_MODE = 0, vtol_mode::TRANSITION_FRONT_P1, vtol_mode::TRANSITION_BACK, vtol_mode::FW_MODE }
 

Private Member Functions

void parameters_update () override
 

Private Attributes

struct {
   float   front_trans_dur_p2
 
   float   fw_pitch_sp_offset
 
_params_tailsitter
 
struct {
   param_t   front_trans_dur_p2
 
   param_t   fw_pitch_sp_offset
 
_params_handles_tailsitter
 
struct {
   vtol_mode   flight_mode
 vtol flight mode, defined by enum vtol_mode More...
 
   hrt_abstime   transition_start
 absoulte time at which front transition started More...
 
_vtol_schedule
 
matrix::Quatf _q_trans_start
 
matrix::Quatf _q_trans_sp
 
matrix::Vector3f _trans_rot_axis
 

Additional Inherited Members

- Protected Member Functions inherited from VtolType
bool set_idle_mc ()
 Sets mc motor minimum pwm to VT_IDLE_PWM_MC which ensures that they are spinning in mc mode. More...
 
bool set_idle_fw ()
 Sets mc motor minimum pwm to PWM_MIN which ensures that the motors stop spinning on zero throttle in fw mode. More...
 
motor_state set_motor_state (const motor_state current_state, const motor_state next_state, const int value=0)
 Sets state of a selection of motors, see struct motor_state. More...
 
- Protected Attributes inherited from VtolType
VtolAttitudeControl_attc
 
mode _vtol_mode
 
struct vehicle_attitude_s_v_att
 
struct vehicle_attitude_setpoint_s_v_att_sp
 
struct vehicle_attitude_setpoint_s_mc_virtual_att_sp
 
struct vehicle_attitude_setpoint_s_fw_virtual_att_sp
 
struct vehicle_control_mode_s_v_control_mode
 
struct vtol_vehicle_status_s_vtol_vehicle_status
 
struct actuator_controls_s_actuators_out_0
 
struct actuator_controls_s_actuators_out_1
 
struct actuator_controls_s_actuators_mc_in
 
struct actuator_controls_s_actuators_fw_in
 
struct vehicle_local_position_s_local_pos
 
struct vehicle_local_position_setpoint_s_local_pos_sp
 
struct airspeed_validated_s_airspeed_validated
 
struct tecs_status_s_tecs_status
 
struct vehicle_land_detected_s_land_detected
 
struct Params_params
 
bool flag_idle_mc = false
 
bool _pusher_active = false
 
float _mc_roll_weight = 1.0f
 
float _mc_pitch_weight = 1.0f
 
float _mc_yaw_weight = 1.0f
 
float _mc_throttle_weight = 1.0f
 
float _thrust_transition = 0.0f
 
float _ra_hrate = 0.0f
 
float _ra_hrate_sp = 0.0f
 
bool _flag_was_in_trans_mode = false
 
hrt_abstime _trans_finished_ts = 0
 
bool _tecs_running = false
 
hrt_abstime _tecs_running_ts = 0
 
motor_state _motor_state = motor_state::DISABLED
 
- Static Protected Attributes inherited from VtolType
static constexpr const int num_outputs_max = 8
 

Detailed Description

Definition at line 51 of file tailsitter.h.

Member Enumeration Documentation

◆ vtol_mode

enum Tailsitter::vtol_mode
strongprivate
Enumerator
MC_MODE 

vtol is in multicopter mode

TRANSITION_FRONT_P1 

vtol is in front transition part 1 mode

TRANSITION_BACK 

vtol is in back transition mode

FW_MODE 

vtol is in fixed wing mode

Definition at line 76 of file tailsitter.h.

Constructor & Destructor Documentation

◆ Tailsitter()

Tailsitter::Tailsitter ( VtolAttitudeControl _att_controller)

Definition at line 52 of file tailsitter.cpp.

References VtolType::_flag_was_in_trans_mode, VtolType::_mc_pitch_weight, VtolType::_mc_roll_weight, VtolType::_mc_yaw_weight, _params_handles_tailsitter, _vtol_schedule, MC_MODE, and param_find().

Here is the call graph for this function:

◆ ~Tailsitter()

Tailsitter::~Tailsitter ( )
overridedefault

Member Function Documentation

◆ fill_actuator_outputs()

void Tailsitter::fill_actuator_outputs ( )
overridevirtual

Write data to actuator output topic.

Implements VtolType.

Definition at line 287 of file tailsitter.cpp.

References VtolType::_actuators_fw_in, VtolType::_actuators_mc_in, VtolType::_actuators_out_0, VtolType::_actuators_out_1, VtolType::_mc_pitch_weight, VtolType::_mc_roll_weight, VtolType::_mc_yaw_weight, VtolType::_params, _vtol_schedule, actuator_controls_s::control, Params::elevons_mc_lock, FW_MODE, hrt_absolute_time(), MC_MODE, actuator_controls_s::timestamp, and actuator_controls_s::timestamp_sample.

Here is the call graph for this function:

◆ parameters_update()

void Tailsitter::parameters_update ( )
overrideprivatevirtual

Implements VtolType.

Definition at line 69 of file tailsitter.cpp.

References _params_handles_tailsitter, _params_tailsitter, param_get(), and math::radians().

Here is the call graph for this function:

◆ update_fw_state()

void Tailsitter::update_fw_state ( )
overridevirtual

Update fixed wing state.

Reimplemented from VtolType.

Definition at line 273 of file tailsitter.cpp.

References VtolType::_mc_roll_weight, VtolType::_params, Params::diff_thrust, and VtolType::update_fw_state().

Here is the call graph for this function:

◆ update_transition_state()

◆ update_vtol_state()

◆ waiting_on_tecs()

void Tailsitter::waiting_on_tecs ( )
overridevirtual

Special handling opportunity for the time right after transition to FW before TECS is running.

Reimplemented from VtolType.

Definition at line 267 of file tailsitter.cpp.

References VtolType::_thrust_transition, VtolType::_v_att_sp, and vehicle_attitude_setpoint_s::thrust_body.

Member Data Documentation

◆ _params_handles_tailsitter

struct { ... } Tailsitter::_params_handles_tailsitter

Referenced by parameters_update(), and Tailsitter().

◆ _params_tailsitter

struct { ... } Tailsitter::_params_tailsitter

◆ _q_trans_sp

matrix::Quatf Tailsitter::_q_trans_sp
private

Definition at line 89 of file tailsitter.h.

Referenced by update_transition_state().

◆ _q_trans_start

matrix::Quatf Tailsitter::_q_trans_start
private

Definition at line 88 of file tailsitter.h.

Referenced by update_transition_state().

◆ _trans_rot_axis

matrix::Vector3f Tailsitter::_trans_rot_axis
private

Definition at line 90 of file tailsitter.h.

Referenced by update_transition_state().

◆ _vtol_schedule

struct { ... } Tailsitter::_vtol_schedule

◆ flight_mode

vtol_mode Tailsitter::flight_mode

vtol flight mode, defined by enum vtol_mode

Definition at line 84 of file tailsitter.h.

◆ front_trans_dur_p2 [1/2]

float Tailsitter::front_trans_dur_p2

Definition at line 67 of file tailsitter.h.

◆ front_trans_dur_p2 [2/2]

param_t Tailsitter::front_trans_dur_p2

Definition at line 72 of file tailsitter.h.

◆ fw_pitch_sp_offset [1/2]

float Tailsitter::fw_pitch_sp_offset

Definition at line 68 of file tailsitter.h.

◆ fw_pitch_sp_offset [2/2]

param_t Tailsitter::fw_pitch_sp_offset

Definition at line 73 of file tailsitter.h.

◆ transition_start

hrt_abstime Tailsitter::transition_start

absoulte time at which front transition started

Definition at line 85 of file tailsitter.h.


The documentation for this class was generated from the following files: