PX4 Firmware
PX4 Autopilot Software http://px4.io
VtolType Class Referenceabstract

#include <vtol_type.h>

Inheritance diagram for VtolType:
Collaboration diagram for VtolType:

Classes

struct  _disarmed_pwm_values
 
struct  _max_mc_pwm_values
 
struct  _min_mc_pwm_values
 Stores the max pwm values given by the system. More...
 

Public Member Functions

 VtolType (VtolAttitudeControl *att_controller)
 
 VtolType (const VtolType &)=delete
 
VtolTypeoperator= (const VtolType &)=delete
 
virtual ~VtolType ()=default
 
bool init ()
 Initialise. More...
 
virtual void update_vtol_state ()=0
 Update vtol state. More...
 
virtual void update_transition_state ()=0
 Update transition state. More...
 
virtual void update_mc_state ()
 Update multicopter state. More...
 
virtual void update_fw_state ()
 Update fixed wing state. More...
 
virtual void fill_actuator_outputs ()=0
 Write control values to actuator output topics. More...
 
virtual void waiting_on_tecs ()
 Special handling opportunity for the time right after transition to FW before TECS is running. 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 ()
 
virtual void parameters_update ()=0
 

Protected Member Functions

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

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

static constexpr const int num_outputs_max = 8
 

Private Member Functions

bool apply_pwm_limits (struct pwm_output_values &pwm_values, pwm_limit_type type)
 Adjust minimum/maximum pwm values for the output channels. More...
 
bool is_channel_set (const int channel, const int target)
 Determines if channel is set in target. More...
 

Detailed Description

Definition at line 110 of file vtol_type.h.

Constructor & Destructor Documentation

◆ VtolType() [1/2]

◆ VtolType() [2/2]

VtolType::VtolType ( const VtolType )
delete

◆ ~VtolType()

virtual VtolType::~VtolType ( )
virtualdefault

Member Function Documentation

◆ apply_pwm_limits()

bool VtolType::apply_pwm_limits ( struct pwm_output_values pwm_values,
pwm_limit_type  type 
)
private

Adjust minimum/maximum pwm values for the output channels.

Parameters
pwm_output_valuesStruct containing the limit values for each channel
[in]typeSpecifies if min or max limits are adjusted.
Returns
True on success.

Definition at line 282 of file vtol_type.cpp.

References fd, OK, PWM_OUTPUT0_DEVICE_PATH, PWM_SERVO_SET_MAX_PWM, PWM_SERVO_SET_MIN_PWM, px4_close(), px4_ioctl(), px4_open(), and TYPE_MINIMUM.

Referenced by set_idle_fw(), set_idle_mc(), and set_motor_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ can_transition_on_ground()

bool VtolType::can_transition_on_ground ( )

Returns true if we're allowed to do a mode transition on the ground.

Definition at line 181 of file vtol_type.cpp.

References _land_detected, _v_control_mode, vehicle_control_mode_s::flag_armed, and vehicle_land_detected_s::landed.

Referenced by Tiltrotor::update_vtol_state(), Tailsitter::update_vtol_state(), and Standard::update_vtol_state().

Here is the caller graph for this function:

◆ check_quadchute_condition()

◆ fill_actuator_outputs()

virtual void VtolType::fill_actuator_outputs ( )
pure virtual

Write control values to actuator output topics.

Implemented in Standard, Tailsitter, and Tiltrotor.

Referenced by VtolAttitudeControl::Run().

Here is the caller graph for this function:

◆ get_mode()

mode VtolType::get_mode ( )
inline

Definition at line 168 of file vtol_type.h.

References mpu9x50::parameters_update().

Referenced by VtolAttitudeControl::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

bool VtolType::init ( )

Initialise.

Definition at line 80 of file vtol_type.cpp.

References fd, PWM_OUTPUT0_DEVICE_PATH, PWM_SERVO_GET_DISARMED_PWM, PWM_SERVO_GET_MAX_PWM, PWM_SERVO_GET_MIN_PWM, px4_close(), px4_ioctl(), and px4_open().

Referenced by VtolAttitudeControl::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_channel_set()

bool VtolType::is_channel_set ( const int  channel,
const int  target 
)
private

Determines if channel is set in target.

Parameters
[in]channelThe channel
[in]targetThe target to check on.
Returns
True if motor off channel, False otherwise.

Definition at line 363 of file vtol_type.cpp.

References num_outputs_max.

Referenced by set_idle_fw(), set_idle_mc(), and set_motor_state().

Here is the caller graph for this function:

◆ operator=()

VtolType& VtolType::operator= ( const VtolType )
delete

◆ parameters_update()

virtual void VtolType::parameters_update ( )
pure virtual

Implemented in Standard, Tiltrotor, and Tailsitter.

Referenced by VtolAttitudeControl::parameters_update().

Here is the caller graph for this function:

◆ set_idle_fw()

bool VtolType::set_idle_fw ( )
protected

Sets mc motor minimum pwm to PWM_MIN which ensures that the motors stop spinning on zero throttle in fw mode.

Returns
true on success

Definition at line 264 of file vtol_type.cpp.

References _params, apply_pwm_limits(), pwm_output_values::channel_count, is_channel_set(), num_outputs_max, PWM_MOTOR_OFF, TYPE_MINIMUM, pwm_output_values::values, and Params::vtol_motor_id.

Referenced by update_fw_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_idle_mc()

bool VtolType::set_idle_mc ( )
protected

Sets mc motor minimum pwm to VT_IDLE_PWM_MC which ensures that they are spinning in mc mode.

Returns
true on success

Definition at line 245 of file vtol_type.cpp.

References _params, apply_pwm_limits(), pwm_output_values::channel_count, Params::idle_pwm_mc, is_channel_set(), num_outputs_max, TYPE_MINIMUM, pwm_output_values::values, and Params::vtol_motor_id.

Referenced by update_mc_state(), Tiltrotor::update_transition_state(), and Tailsitter::update_transition_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_motor_state()

motor_state VtolType::set_motor_state ( const motor_state  current_state,
const motor_state  next_state,
const int  value = 0 
)
protected

Sets state of a selection of motors, see struct motor_state.

Parameters
[in]current_stateThe current motor state
[in]next_stateThe next state
[in]valueDesired pwm value if next_state = motor_state::VALUE
Returns
next_state if succesfull, otherwise current_state

Definition at line 312 of file vtol_type.cpp.

References _params, apply_pwm_limits(), pwm_output_values::channel_count, DISABLED, ENABLED, Params::fw_motors_off, IDLE, Params::idle_pwm_mc, is_channel_set(), num_outputs_max, TYPE_MAXIMUM, VALUE, pwm_output_values::values, and Params::vtol_motor_id.

Referenced by update_fw_state(), update_mc_state(), Tiltrotor::update_transition_state(), and Standard::update_transition_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_fw_state()

void VtolType::update_fw_state ( )
virtual

Update fixed wing state.

Reimplemented in Standard, Tailsitter, and Tiltrotor.

Definition at line 140 of file vtol_type.cpp.

References _fw_virtual_att_sp, _mc_pitch_weight, _mc_roll_weight, _mc_yaw_weight, _motor_state, _tecs_running, _tecs_running_ts, _tecs_status, _trans_finished_ts, _v_att_sp, _v_control_mode, check_quadchute_condition(), DISABLED, vehicle_control_mode_s::flag_control_altitude_enabled, flag_idle_mc, hrt_absolute_time(), set_idle_fw(), set_motor_state(), vehicle_attitude_setpoint_s::timestamp, tecs_status_s::timestamp, and waiting_on_tecs().

Referenced by VtolAttitudeControl::Run(), Tiltrotor::update_fw_state(), Tailsitter::update_fw_state(), and Standard::update_fw_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_mc_state()

void VtolType::update_mc_state ( )
virtual

Update multicopter state.

Reimplemented in Standard, and Tiltrotor.

Definition at line 121 of file vtol_type.cpp.

References _mc_pitch_weight, _mc_roll_weight, _mc_throttle_weight, _mc_virtual_att_sp, _mc_yaw_weight, _motor_state, _v_att_sp, ENABLED, flag_idle_mc, set_idle_mc(), and set_motor_state().

Referenced by VtolAttitudeControl::Run(), Tiltrotor::update_mc_state(), and Standard::update_mc_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_transition_state()

void VtolType::update_transition_state ( )
pure virtual

Update transition state.

Implemented in Standard, Tailsitter, and Tiltrotor.

Definition at line 176 of file vtol_type.cpp.

References check_quadchute_condition().

Referenced by VtolAttitudeControl::Run(), Tiltrotor::update_transition_state(), and Standard::update_transition_state().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_vtol_state()

virtual void VtolType::update_vtol_state ( )
pure virtual

Update vtol state.

Implemented in Standard, Tailsitter, and Tiltrotor.

Referenced by VtolAttitudeControl::Run().

Here is the caller graph for this function:

◆ waiting_on_tecs()

virtual void VtolType::waiting_on_tecs ( )
inlinevirtual

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

Reimplemented in Standard, Tailsitter, and Tiltrotor.

Definition at line 154 of file vtol_type.h.

Referenced by update_fw_state().

Here is the caller graph for this function:

Member Data Documentation

◆ _actuators_fw_in

struct actuator_controls_s* VtolType::_actuators_fw_in
protected

◆ _actuators_mc_in

struct actuator_controls_s* VtolType::_actuators_mc_in
protected

◆ _actuators_out_0

struct actuator_controls_s* VtolType::_actuators_out_0
protected

◆ _actuators_out_1

struct actuator_controls_s* VtolType::_actuators_out_1
protected

◆ _airspeed_validated

◆ _attc

◆ _flag_was_in_trans_mode

bool VtolType::_flag_was_in_trans_mode = false
protected

◆ _fw_virtual_att_sp

struct vehicle_attitude_setpoint_s* VtolType::_fw_virtual_att_sp
protected

Definition at line 181 of file vtol_type.h.

Referenced by update_fw_state(), Tailsitter::update_transition_state(), and VtolType().

◆ _land_detected

struct vehicle_land_detected_s* VtolType::_land_detected
protected

Definition at line 192 of file vtol_type.h.

Referenced by can_transition_on_ground(), check_quadchute_condition(), and VtolType().

◆ _local_pos

struct vehicle_local_position_s* VtolType::_local_pos
protected

Definition at line 188 of file vtol_type.h.

Referenced by check_quadchute_condition(), Standard::update_vtol_state(), and VtolType().

◆ _local_pos_sp

struct vehicle_local_position_setpoint_s* VtolType::_local_pos_sp
protected

Definition at line 189 of file vtol_type.h.

Referenced by check_quadchute_condition(), and VtolType().

◆ _mc_pitch_weight

◆ _mc_roll_weight

◆ _mc_throttle_weight

◆ _mc_virtual_att_sp

◆ _mc_yaw_weight

◆ _motor_state

◆ _params

◆ _pusher_active

bool VtolType::_pusher_active = false
protected

Definition at line 198 of file vtol_type.h.

Referenced by Standard::Standard().

◆ _ra_hrate

float VtolType::_ra_hrate = 0.0f
protected

Definition at line 207 of file vtol_type.h.

Referenced by check_quadchute_condition().

◆ _ra_hrate_sp

float VtolType::_ra_hrate_sp = 0.0f
protected

Definition at line 208 of file vtol_type.h.

Referenced by check_quadchute_condition().

◆ _tecs_running

bool VtolType::_tecs_running = false
protected

Definition at line 214 of file vtol_type.h.

Referenced by check_quadchute_condition(), and update_fw_state().

◆ _tecs_running_ts

hrt_abstime VtolType::_tecs_running_ts = 0
protected

Definition at line 215 of file vtol_type.h.

Referenced by update_fw_state().

◆ _tecs_status

struct tecs_status_s* VtolType::_tecs_status
protected

Definition at line 191 of file vtol_type.h.

Referenced by check_quadchute_condition(), update_fw_state(), and VtolType().

◆ _thrust_transition

float VtolType::_thrust_transition = 0.0f
protected

◆ _trans_finished_ts

hrt_abstime VtolType::_trans_finished_ts = 0
protected

Definition at line 212 of file vtol_type.h.

Referenced by update_fw_state(), and Standard::update_vtol_state().

◆ _v_att

◆ _v_att_sp

◆ _v_control_mode

struct vehicle_control_mode_s* VtolType::_v_control_mode
protected

◆ _vtol_mode

mode VtolType::_vtol_mode
protected

◆ _vtol_vehicle_status

struct vtol_vehicle_status_s* VtolType::_vtol_vehicle_status
protected

◆ flag_idle_mc

bool VtolType::flag_idle_mc = false
protected

◆ num_outputs_max

constexpr const int VtolType::num_outputs_max = 8
staticprotected

Definition at line 176 of file vtol_type.h.

Referenced by is_channel_set(), set_idle_fw(), set_idle_mc(), and set_motor_state().


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