PX4 Firmware
PX4 Autopilot Software http://px4.io
FixedwingAttitudeControl Class Referencefinal

#include <FixedwingAttitudeControl.hpp>

Inheritance diagram for FixedwingAttitudeControl:
Collaboration diagram for FixedwingAttitudeControl:

Public Member Functions

 FixedwingAttitudeControl ()
 
 ~FixedwingAttitudeControl () override
 
int print_status () override
 
void Run () override
 
bool init ()
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 

Private Member Functions

 DEFINE_PARAMETERS ((ParamFloat< px4::params::FW_ACRO_X_MAX >) _param_fw_acro_x_max,(ParamFloat< px4::params::FW_ACRO_Y_MAX >) _param_fw_acro_y_max,(ParamFloat< px4::params::FW_ACRO_Z_MAX >) _param_fw_acro_z_max,(ParamFloat< px4::params::FW_AIRSPD_MAX >) _param_fw_airspd_max,(ParamFloat< px4::params::FW_AIRSPD_MIN >) _param_fw_airspd_min,(ParamFloat< px4::params::FW_AIRSPD_TRIM >) _param_fw_airspd_trim,(ParamInt< px4::params::FW_ARSP_MODE >) _param_fw_arsp_mode,(ParamBool< px4::params::FW_BAT_SCALE_EN >) _param_fw_bat_scale_en,(ParamFloat< px4::params::FW_DTRIM_P_FLPS >) _param_fw_dtrim_p_flps,(ParamFloat< px4::params::FW_DTRIM_P_VMAX >) _param_fw_dtrim_p_vmax,(ParamFloat< px4::params::FW_DTRIM_P_VMIN >) _param_fw_dtrim_p_vmin,(ParamFloat< px4::params::FW_DTRIM_R_FLPS >) _param_fw_dtrim_r_flps,(ParamFloat< px4::params::FW_DTRIM_R_VMAX >) _param_fw_dtrim_r_vmax,(ParamFloat< px4::params::FW_DTRIM_R_VMIN >) _param_fw_dtrim_r_vmin,(ParamFloat< px4::params::FW_DTRIM_Y_VMAX >) _param_fw_dtrim_y_vmax,(ParamFloat< px4::params::FW_DTRIM_Y_VMIN >) _param_fw_dtrim_y_vmin,(ParamFloat< px4::params::FW_FLAPERON_SCL >) _param_fw_flaperon_scl,(ParamFloat< px4::params::FW_FLAPS_LND_SCL >) _param_fw_flaps_lnd_scl,(ParamFloat< px4::params::FW_FLAPS_SCL >) _param_fw_flaps_scl,(ParamFloat< px4::params::FW_FLAPS_TO_SCL >) _param_fw_flaps_to_scl,(ParamFloat< px4::params::FW_MAN_P_MAX >) _param_fw_man_p_max,(ParamFloat< px4::params::FW_MAN_P_SC >) _param_fw_man_p_sc,(ParamFloat< px4::params::FW_MAN_R_MAX >) _param_fw_man_r_max,(ParamFloat< px4::params::FW_MAN_R_SC >) _param_fw_man_r_sc,(ParamFloat< px4::params::FW_MAN_Y_SC >) _param_fw_man_y_sc,(ParamFloat< px4::params::FW_P_RMAX_NEG >) _param_fw_p_rmax_neg,(ParamFloat< px4::params::FW_P_RMAX_POS >) _param_fw_p_rmax_pos,(ParamFloat< px4::params::FW_P_TC >) _param_fw_p_tc,(ParamFloat< px4::params::FW_PR_FF >) _param_fw_pr_ff,(ParamFloat< px4::params::FW_PR_I >) _param_fw_pr_i,(ParamFloat< px4::params::FW_PR_IMAX >) _param_fw_pr_imax,(ParamFloat< px4::params::FW_PR_P >) _param_fw_pr_p,(ParamFloat< px4::params::FW_PSP_OFF >) _param_fw_psp_off,(ParamFloat< px4::params::FW_RATT_TH >) _param_fw_ratt_th,(ParamFloat< px4::params::FW_R_RMAX >) _param_fw_r_rmax,(ParamFloat< px4::params::FW_R_TC >) _param_fw_r_tc,(ParamFloat< px4::params::FW_RLL_TO_YAW_FF >) _param_fw_rll_to_yaw_ff,(ParamFloat< px4::params::FW_RR_FF >) _param_fw_rr_ff,(ParamFloat< px4::params::FW_RR_I >) _param_fw_rr_i,(ParamFloat< px4::params::FW_RR_IMAX >) _param_fw_rr_imax,(ParamFloat< px4::params::FW_RR_P >) _param_fw_rr_p,(ParamFloat< px4::params::FW_RSP_OFF >) _param_fw_rsp_off,(ParamBool< px4::params::FW_W_EN >) _param_fw_w_en,(ParamFloat< px4::params::FW_W_RMAX >) _param_fw_w_rmax,(ParamFloat< px4::params::FW_WR_FF >) _param_fw_wr_ff,(ParamFloat< px4::params::FW_WR_I >) _param_fw_wr_i,(ParamFloat< px4::params::FW_WR_IMAX >) _param_fw_wr_imax,(ParamFloat< px4::params::FW_WR_P >) _param_fw_wr_p,(ParamFloat< px4::params::FW_Y_RMAX >) _param_fw_y_rmax,(ParamFloat< px4::params::FW_YR_FF >) _param_fw_yr_ff,(ParamFloat< px4::params::FW_YR_I >) _param_fw_yr_i,(ParamFloat< px4::params::FW_YR_IMAX >) _param_fw_yr_imax,(ParamFloat< px4::params::FW_YR_P >) _param_fw_yr_p,(ParamFloat< px4::params::TRIM_PITCH >) _param_trim_pitch,(ParamFloat< px4::params::TRIM_ROLL >) _param_trim_roll,(ParamFloat< px4::params::TRIM_YAW >) _param_trim_yaw) ECL_RollController _roll_ctrl
 
void control_flaps (const float dt)
 
int parameters_update ()
 Update our local parameter cache. More...
 
void vehicle_control_mode_poll ()
 
void vehicle_manual_poll ()
 
void vehicle_attitude_setpoint_poll ()
 
void vehicle_rates_setpoint_poll ()
 
void vehicle_status_poll ()
 
void vehicle_land_detected_poll ()
 
float get_airspeed_and_update_scaling ()
 

Private Attributes

uORB::SubscriptionCallbackWorkItem _att_sub {this, ORB_ID(vehicle_attitude)}
 vehicle attitude More...
 
uORB::Subscription _att_sp_sub {ORB_ID(vehicle_attitude_setpoint)}
 vehicle attitude setpoint More...
 
uORB::Subscription _battery_status_sub {ORB_ID(battery_status)}
 battery status subscription More...
 
uORB::Subscription _global_pos_sub {ORB_ID(vehicle_global_position)}
 global position subscription More...
 
uORB::Subscription _manual_sub {ORB_ID(manual_control_setpoint)}
 notification of manual control updates More...
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 notification of parameter updates More...
 
uORB::Subscription _rates_sp_sub {ORB_ID(vehicle_rates_setpoint)}
 vehicle rates setpoint More...
 
uORB::Subscription _vcontrol_mode_sub {ORB_ID(vehicle_control_mode)}
 vehicle status subscription More...
 
uORB::Subscription _vehicle_land_detected_sub {ORB_ID(vehicle_land_detected)}
 vehicle land detected subscription More...
 
uORB::Subscription _vehicle_status_sub {ORB_ID(vehicle_status)}
 vehicle status subscription More...
 
uORB::Subscription _vehicle_rates_sub {ORB_ID(vehicle_angular_velocity)}
 
uORB::SubscriptionData< airspeed_validated_s_airspeed_validated_sub {ORB_ID(airspeed_validated)}
 
uORB::Publication< actuator_controls_s_actuators_2_pub {ORB_ID(actuator_controls_2)}
 actuator control group 1 setpoint (Airframe) More...
 
uORB::Publication< vehicle_rates_setpoint_s_rate_sp_pub {ORB_ID(vehicle_rates_setpoint)}
 rate setpoint publication More...
 
uORB::PublicationMulti< rate_ctrl_status_s_rate_ctrl_status_pub {ORB_ID(rate_ctrl_status)}
 rate controller status publication More...
 
orb_id_t _attitude_setpoint_id {nullptr}
 
orb_advert_t _attitude_sp_pub {nullptr}
 attitude setpoint point More...
 
orb_id_t _actuators_id {nullptr}
 pointer to correct actuator controls0 uORB metadata structure More...
 
orb_advert_t _actuators_0_pub {nullptr}
 actuator control group 0 setpoint More...
 
actuator_controls_s _actuators {}
 actuator control inputs More...
 
actuator_controls_s _actuators_airframe {}
 actuator control inputs More...
 
manual_control_setpoint_s _manual {}
 r/c channel data More...
 
vehicle_attitude_s _att {}
 vehicle attitude setpoint More...
 
vehicle_attitude_setpoint_s _att_sp {}
 vehicle attitude setpoint More...
 
vehicle_control_mode_s _vcontrol_mode {}
 vehicle control mode More...
 
vehicle_global_position_s _global_pos {}
 global position More...
 
vehicle_rates_setpoint_s _rates_sp {}
 
vehicle_status_s _vehicle_status {}
 vehicle status More...
 
perf_counter_t _loop_perf
 loop performance counter More...
 
float _flaps_applied {0.0f}
 
float _flaperons_applied {0.0f}
 
float _airspeed_scaling {1.0f}
 
bool _landed {true}
 
float _battery_scale {1.0f}
 
bool _flag_control_attitude_enabled_last {false}
 
bool _is_tailsitter {false}
 
ECL_PitchController _pitch_ctrl
 
ECL_YawController _yaw_ctrl
 
ECL_WheelController _wheel_ctrl
 

Detailed Description

Definition at line 75 of file FixedwingAttitudeControl.hpp.

Constructor & Destructor Documentation

◆ FixedwingAttitudeControl()

FixedwingAttitudeControl::FixedwingAttitudeControl ( )

Definition at line 43 of file FixedwingAttitudeControl.cpp.

References _pitch_ctrl, _yaw_ctrl, parameters_update(), math::radians(), ECL_Controller::set_max_rate(), ECL_PitchController::set_max_rate_neg(), ECL_PitchController::set_max_rate_pos(), and vehicle_status_poll().

Referenced by task_spawn().

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

◆ ~FixedwingAttitudeControl()

FixedwingAttitudeControl::~FixedwingAttitudeControl ( )
override

Definition at line 61 of file FixedwingAttitudeControl.cpp.

References _loop_perf, and perf_free().

Here is the call graph for this function:

Member Function Documentation

◆ control_flaps()

void FixedwingAttitudeControl::control_flaps ( const float  dt)
private

Definition at line 664 of file FixedwingAttitudeControl.cpp.

References _att_sp, _flaperons_applied, _flaps_applied, _manual, _vcontrol_mode, vehicle_attitude_setpoint_s::apply_flaps, manual_control_setpoint_s::aux2, f(), vehicle_control_mode_s::flag_control_auto_enabled, vehicle_control_mode_s::flag_control_manual_enabled, and manual_control_setpoint_s::flaps.

Referenced by Run().

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

◆ custom_command()

int FixedwingAttitudeControl::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 752 of file FixedwingAttitudeControl.cpp.

References print_usage().

Here is the call graph for this function:

◆ DEFINE_PARAMETERS()

FixedwingAttitudeControl::DEFINE_PARAMETERS ( (ParamFloat< px4::params::FW_ACRO_X_MAX >)  _param_fw_acro_x_max,
(ParamFloat< px4::params::FW_ACRO_Y_MAX >)  _param_fw_acro_y_max,
(ParamFloat< px4::params::FW_ACRO_Z_MAX >)  _param_fw_acro_z_max,
(ParamFloat< px4::params::FW_AIRSPD_MAX >)  _param_fw_airspd_max,
(ParamFloat< px4::params::FW_AIRSPD_MIN >)  _param_fw_airspd_min,
(ParamFloat< px4::params::FW_AIRSPD_TRIM >)  _param_fw_airspd_trim,
(ParamInt< px4::params::FW_ARSP_MODE >)  _param_fw_arsp_mode,
(ParamBool< px4::params::FW_BAT_SCALE_EN >)  _param_fw_bat_scale_en,
(ParamFloat< px4::params::FW_DTRIM_P_FLPS >)  _param_fw_dtrim_p_flps,
(ParamFloat< px4::params::FW_DTRIM_P_VMAX >)  _param_fw_dtrim_p_vmax,
(ParamFloat< px4::params::FW_DTRIM_P_VMIN >)  _param_fw_dtrim_p_vmin,
(ParamFloat< px4::params::FW_DTRIM_R_FLPS >)  _param_fw_dtrim_r_flps,
(ParamFloat< px4::params::FW_DTRIM_R_VMAX >)  _param_fw_dtrim_r_vmax,
(ParamFloat< px4::params::FW_DTRIM_R_VMIN >)  _param_fw_dtrim_r_vmin,
(ParamFloat< px4::params::FW_DTRIM_Y_VMAX >)  _param_fw_dtrim_y_vmax,
(ParamFloat< px4::params::FW_DTRIM_Y_VMIN >)  _param_fw_dtrim_y_vmin,
(ParamFloat< px4::params::FW_FLAPERON_SCL >)  _param_fw_flaperon_scl,
(ParamFloat< px4::params::FW_FLAPS_LND_SCL >)  _param_fw_flaps_lnd_scl,
(ParamFloat< px4::params::FW_FLAPS_SCL >)  _param_fw_flaps_scl,
(ParamFloat< px4::params::FW_FLAPS_TO_SCL >)  _param_fw_flaps_to_scl,
(ParamFloat< px4::params::FW_MAN_P_MAX >)  _param_fw_man_p_max,
(ParamFloat< px4::params::FW_MAN_P_SC >)  _param_fw_man_p_sc,
(ParamFloat< px4::params::FW_MAN_R_MAX >)  _param_fw_man_r_max,
(ParamFloat< px4::params::FW_MAN_R_SC >)  _param_fw_man_r_sc,
(ParamFloat< px4::params::FW_MAN_Y_SC >)  _param_fw_man_y_sc,
(ParamFloat< px4::params::FW_P_RMAX_NEG >)  _param_fw_p_rmax_neg,
(ParamFloat< px4::params::FW_P_RMAX_POS >)  _param_fw_p_rmax_pos,
(ParamFloat< px4::params::FW_P_TC >)  _param_fw_p_tc,
(ParamFloat< px4::params::FW_PR_FF >)  _param_fw_pr_ff,
(ParamFloat< px4::params::FW_PR_I >)  _param_fw_pr_i,
(ParamFloat< px4::params::FW_PR_IMAX >)  _param_fw_pr_imax,
(ParamFloat< px4::params::FW_PR_P >)  _param_fw_pr_p,
(ParamFloat< px4::params::FW_PSP_OFF >)  _param_fw_psp_off,
(ParamFloat< px4::params::FW_RATT_TH >)  _param_fw_ratt_th,
(ParamFloat< px4::params::FW_R_RMAX >)  _param_fw_r_rmax,
(ParamFloat< px4::params::FW_R_TC >)  _param_fw_r_tc,
(ParamFloat< px4::params::FW_RLL_TO_YAW_FF >)  _param_fw_rll_to_yaw_ff,
(ParamFloat< px4::params::FW_RR_FF >)  _param_fw_rr_ff,
(ParamFloat< px4::params::FW_RR_I >)  _param_fw_rr_i,
(ParamFloat< px4::params::FW_RR_IMAX >)  _param_fw_rr_imax,
(ParamFloat< px4::params::FW_RR_P >)  _param_fw_rr_p,
(ParamFloat< px4::params::FW_RSP_OFF >)  _param_fw_rsp_off,
(ParamBool< px4::params::FW_W_EN >)  _param_fw_w_en,
(ParamFloat< px4::params::FW_W_RMAX >)  _param_fw_w_rmax,
(ParamFloat< px4::params::FW_WR_FF >)  _param_fw_wr_ff,
(ParamFloat< px4::params::FW_WR_I >)  _param_fw_wr_i,
(ParamFloat< px4::params::FW_WR_IMAX >)  _param_fw_wr_imax,
(ParamFloat< px4::params::FW_WR_P >)  _param_fw_wr_p,
(ParamFloat< px4::params::FW_Y_RMAX >)  _param_fw_y_rmax,
(ParamFloat< px4::params::FW_YR_FF >)  _param_fw_yr_ff,
(ParamFloat< px4::params::FW_YR_I >)  _param_fw_yr_i,
(ParamFloat< px4::params::FW_YR_IMAX >)  _param_fw_yr_imax,
(ParamFloat< px4::params::FW_YR_P >)  _param_fw_yr_p,
(ParamFloat< px4::params::TRIM_PITCH >)  _param_trim_pitch,
(ParamFloat< px4::params::TRIM_ROLL >)  _param_trim_roll,
(ParamFloat< px4::params::TRIM_YAW >)  _param_trim_yaw 
)
private

◆ get_airspeed_and_update_scaling()

float FixedwingAttitudeControl::get_airspeed_and_update_scaling ( )
private

Definition at line 259 of file FixedwingAttitudeControl.cpp.

References _airspeed_scaling, _airspeed_validated_sub, _vehicle_status, math::constrain(), f(), uORB::SubscriptionData< T >::get(), hrt_elapsed_time(), vehicle_status_s::in_transition_mode, airspeed_validated_s::indicated_airspeed_m_s, vehicle_status_s::is_vtol, math::max(), airspeed_validated_s::timestamp, uORB::SubscriptionData< T >::update(), and vehicle_status_s::vehicle_type.

Referenced by Run().

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

◆ init()

bool FixedwingAttitudeControl::init ( )

Definition at line 67 of file FixedwingAttitudeControl.cpp.

References _att_sub, and uORB::SubscriptionCallback::registerCallback().

Referenced by task_spawn().

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

◆ parameters_update()

int FixedwingAttitudeControl::parameters_update ( )
private

Update our local parameter cache.

Definition at line 78 of file FixedwingAttitudeControl.cpp.

References _pitch_ctrl, _wheel_ctrl, _yaw_ctrl, math::radians(), ECL_Controller::set_integrator_max(), ECL_Controller::set_k_ff(), ECL_Controller::set_k_i(), ECL_Controller::set_k_p(), ECL_Controller::set_max_rate(), and ECL_Controller::set_time_constant().

Referenced by FixedwingAttitudeControl(), and Run().

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

◆ print_status()

int FixedwingAttitudeControl::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 757 of file FixedwingAttitudeControl.cpp.

References _loop_perf, and perf_print_counter().

Here is the call graph for this function:

◆ print_usage()

int FixedwingAttitudeControl::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 764 of file FixedwingAttitudeControl.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ Run()

void FixedwingAttitudeControl::Run ( )
override

Definition at line 295 of file FixedwingAttitudeControl.cpp.

References _actuators, _actuators_0_pub, _actuators_2_pub, _actuators_airframe, _actuators_id, _airspeed_scaling, _att, _att_sp, _att_sub, _battery_scale, _battery_status_sub, _flag_control_attitude_enabled_last, _flaperons_applied, _flaps_applied, _global_pos, _global_pos_sub, _is_tailsitter, _landed, _loop_perf, _manual, _parameter_update_sub, _pitch_ctrl, _rate_ctrl_status_pub, _rate_sp_pub, _rates_sp, _vcontrol_mode, _vehicle_rates_sub, _vehicle_status, _wheel_ctrl, _yaw_ctrl, rate_ctrl_status_s::additional_integ1, ECL_ControlData::airspeed, ECL_ControlData::airspeed_max, ECL_ControlData::airspeed_min, manual_control_setpoint_s::aux1, manual_control_setpoint_s::aux3, ECL_ControlData::body_x_rate, ECL_ControlData::body_y_rate, ECL_ControlData::body_z_rate, math::constrain(), actuator_controls_s::control, ECL_YawController::control_attitude(), ECL_WheelController::control_attitude(), ECL_PitchController::control_attitude(), ECL_YawController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_PitchController::control_bodyrate(), ECL_YawController::control_euler_rate(), ECL_PitchController::control_euler_rate(), control_flaps(), uORB::Subscription::copy(), vehicle_status_s::engine_failure, f(), vehicle_control_mode_s::flag_control_attitude_enabled, vehicle_control_mode_s::flag_control_auto_enabled, vehicle_control_mode_s::flag_control_manual_enabled, vehicle_control_mode_s::flag_control_rates_enabled, vehicle_control_mode_s::flag_control_termination_enabled, vehicle_attitude_setpoint_s::fw_control_yaw, get_airspeed_and_update_scaling(), ECL_Controller::get_desired_bodyrate(), ECL_Controller::get_desired_rate(), ECL_Controller::get_integrator(), math::gradual(), ECL_ControlData::groundspeed, ECL_ControlData::groundspeed_scaler, hrt_absolute_time(), hrt_elapsed_time(), vehicle_status_s::in_transition_mode, vehicle_status_s::is_vtol, ECL_ControlData::lock_integrator, orb_advertise(), orb_publish(), parameters_update(), perf_begin(), perf_end(), matrix::Euler< Type >::phi(), vehicle_rates_setpoint_s::pitch, ECL_ControlData::pitch, vehicle_attitude_setpoint_s::pitch_body, ECL_ControlData::pitch_rate_setpoint, vehicle_attitude_setpoint_s::pitch_reset_integral, ECL_ControlData::pitch_setpoint, rate_ctrl_status_s::pitchspeed_integ, matrix::Euler< Type >::psi(), uORB::Publication< T >::publish(), uORB::PublicationMulti< T >::publish(), vehicle_attitude_s::q, manual_control_setpoint_s::r, math::radians(), ECL_Controller::reset_integrator(), ECL_ControlData::roll, vehicle_rates_setpoint_s::roll, vehicle_attitude_setpoint_s::roll_body, ECL_ControlData::roll_rate_setpoint, vehicle_attitude_setpoint_s::roll_reset_integral, ECL_ControlData::roll_setpoint, rate_ctrl_status_s::rollspeed_integ, ECL_ControlData::scaler, ECL_PitchController::set_bodyrate_setpoint(), ECL_Controller::set_bodyrate_setpoint(), ECL_Controller::set_max_rate(), ECL_PitchController::set_max_rate_neg(), ECL_PitchController::set_max_rate_pos(), matrix::Euler< Type >::theta(), vehicle_rates_setpoint_s::thrust_body, vehicle_attitude_setpoint_s::thrust_body, vehicle_attitude_s::timestamp, rate_ctrl_status_s::timestamp, vehicle_rates_setpoint_s::timestamp, actuator_controls_s::timestamp, actuator_controls_s::timestamp_sample, uORB::SubscriptionCallback::unregisterCallback(), uORB::SubscriptionInterval::update(), uORB::Subscription::update(), uORB::Subscription::updated(), vehicle_attitude_setpoint_poll(), vehicle_control_mode_poll(), vehicle_land_detected_poll(), vehicle_manual_poll(), vehicle_rates_setpoint_poll(), vehicle_status_poll(), vehicle_status_s::vehicle_type, vehicle_global_position_s::vel_e, vehicle_global_position_s::vel_n, vehicle_rates_setpoint_s::yaw, ECL_ControlData::yaw, vehicle_attitude_setpoint_s::yaw_body, ECL_ControlData::yaw_rate_setpoint, vehicle_attitude_setpoint_s::yaw_reset_integral, ECL_ControlData::yaw_setpoint, and rate_ctrl_status_s::yawspeed_integ.

Here is the call graph for this function:

◆ task_spawn()

int FixedwingAttitudeControl::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 729 of file FixedwingAttitudeControl.cpp.

References FixedwingAttitudeControl(), init(), and ll40ls::instance.

Here is the call graph for this function:

◆ vehicle_attitude_setpoint_poll()

void FixedwingAttitudeControl::vehicle_attitude_setpoint_poll ( )
private

Definition at line 202 of file FixedwingAttitudeControl.cpp.

References _att_sp, _att_sp_sub, _rates_sp, vehicle_rates_setpoint_s::thrust_body, vehicle_attitude_setpoint_s::thrust_body, and uORB::Subscription::update().

Referenced by Run().

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

◆ vehicle_control_mode_poll()

void FixedwingAttitudeControl::vehicle_control_mode_poll ( )
private

Definition at line 111 of file FixedwingAttitudeControl.cpp.

References _is_tailsitter, _vcontrol_mode, _vcontrol_mode_sub, _vehicle_status, vehicle_control_mode_s::flag_control_attitude_enabled, vehicle_control_mode_s::flag_control_manual_enabled, vehicle_status_s::in_transition_mode, vehicle_status_s::is_vtol, uORB::Subscription::update(), and vehicle_status_s::vehicle_type.

Referenced by Run().

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

◆ vehicle_land_detected_poll()

void FixedwingAttitudeControl::vehicle_land_detected_poll ( )
private

Definition at line 248 of file FixedwingAttitudeControl.cpp.

References _landed, _vehicle_land_detected_sub, uORB::Subscription::copy(), and uORB::Subscription::updated().

Referenced by Run().

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

◆ vehicle_manual_poll()

void FixedwingAttitudeControl::vehicle_manual_poll ( )
private

Definition at line 128 of file FixedwingAttitudeControl.cpp.

References _actuators, _att_sp, _attitude_setpoint_id, _attitude_sp_pub, _is_tailsitter, _manual, _manual_sub, _rate_sp_pub, _rates_sp, _vcontrol_mode, _vehicle_status, math::constrain(), actuator_controls_s::control, uORB::Subscription::copy(), vehicle_control_mode_s::flag_control_attitude_enabled, vehicle_control_mode_s::flag_control_climb_rate_enabled, vehicle_control_mode_s::flag_control_manual_enabled, vehicle_control_mode_s::flag_control_offboard_enabled, vehicle_control_mode_s::flag_control_rates_enabled, vehicle_control_mode_s::flag_control_rattitude_enabled, hrt_absolute_time(), vehicle_status_s::in_transition_mode, is_fixed_wing(), orb_advertise(), orb_publish(), vehicle_rates_setpoint_s::pitch, vehicle_attitude_setpoint_s::pitch_body, uORB::Publication< T >::publish(), vehicle_attitude_setpoint_s::q_d, vehicle_attitude_setpoint_s::q_d_valid, manual_control_setpoint_s::r, math::radians(), vehicle_rates_setpoint_s::roll, vehicle_attitude_setpoint_s::roll_body, vehicle_rates_setpoint_s::thrust_body, vehicle_attitude_setpoint_s::thrust_body, vehicle_rates_setpoint_s::timestamp, vehicle_attitude_setpoint_s::timestamp, vehicle_status_s::vehicle_type, VEHICLE_TYPE_FIXED_WING, manual_control_setpoint_s::x, manual_control_setpoint_s::y, vehicle_rates_setpoint_s::yaw, vehicle_attitude_setpoint_s::yaw_body, and manual_control_setpoint_s::z.

Referenced by Run().

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

◆ vehicle_rates_setpoint_poll()

void FixedwingAttitudeControl::vehicle_rates_setpoint_poll ( )
private

Definition at line 212 of file FixedwingAttitudeControl.cpp.

References _is_tailsitter, _rates_sp, _rates_sp_sub, vehicle_rates_setpoint_s::roll, uORB::Subscription::update(), and vehicle_rates_setpoint_s::yaw.

Referenced by Run().

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

◆ vehicle_status_poll()

void FixedwingAttitudeControl::vehicle_status_poll ( )
private

Definition at line 224 of file FixedwingAttitudeControl.cpp.

References _actuators_id, _attitude_setpoint_id, _is_tailsitter, _vehicle_status, _vehicle_status_sub, vehicle_status_s::is_vtol, ORB_ID, param_find(), param_get(), TAILSITTER, and uORB::Subscription::update().

Referenced by FixedwingAttitudeControl(), and Run().

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

Member Data Documentation

◆ _actuators

actuator_controls_s FixedwingAttitudeControl::_actuators {}
private

actuator control inputs

Definition at line 125 of file FixedwingAttitudeControl.hpp.

Referenced by Run(), and vehicle_manual_poll().

◆ _actuators_0_pub

orb_advert_t FixedwingAttitudeControl::_actuators_0_pub {nullptr}
private

actuator control group 0 setpoint

Definition at line 123 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _actuators_2_pub

uORB::Publication<actuator_controls_s> FixedwingAttitudeControl::_actuators_2_pub {ORB_ID(actuator_controls_2)}
private

actuator control group 1 setpoint (Airframe)

Definition at line 115 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _actuators_airframe

actuator_controls_s FixedwingAttitudeControl::_actuators_airframe {}
private

actuator control inputs

Definition at line 126 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _actuators_id

orb_id_t FixedwingAttitudeControl::_actuators_id {nullptr}
private

pointer to correct actuator controls0 uORB metadata structure

Definition at line 122 of file FixedwingAttitudeControl.hpp.

Referenced by Run(), and vehicle_status_poll().

◆ _airspeed_scaling

float FixedwingAttitudeControl::_airspeed_scaling {1.0f}
private

Definition at line 140 of file FixedwingAttitudeControl.hpp.

Referenced by get_airspeed_and_update_scaling(), and Run().

◆ _airspeed_validated_sub

uORB::SubscriptionData<airspeed_validated_s> FixedwingAttitudeControl::_airspeed_validated_sub {ORB_ID(airspeed_validated)}
private

Definition at line 113 of file FixedwingAttitudeControl.hpp.

Referenced by get_airspeed_and_update_scaling().

◆ _att

vehicle_attitude_s FixedwingAttitudeControl::_att {}
private

vehicle attitude setpoint

Definition at line 128 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _att_sp

vehicle_attitude_setpoint_s FixedwingAttitudeControl::_att_sp {}
private

vehicle attitude setpoint

Definition at line 129 of file FixedwingAttitudeControl.hpp.

Referenced by control_flaps(), Run(), vehicle_attitude_setpoint_poll(), and vehicle_manual_poll().

◆ _att_sp_sub

uORB::Subscription FixedwingAttitudeControl::_att_sp_sub {ORB_ID(vehicle_attitude_setpoint)}
private

vehicle attitude setpoint

Definition at line 102 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_attitude_setpoint_poll().

◆ _att_sub

uORB::SubscriptionCallbackWorkItem FixedwingAttitudeControl::_att_sub {this, ORB_ID(vehicle_attitude)}
private

vehicle attitude

Definition at line 100 of file FixedwingAttitudeControl.hpp.

Referenced by init(), and Run().

◆ _attitude_setpoint_id

orb_id_t FixedwingAttitudeControl::_attitude_setpoint_id {nullptr}
private

Definition at line 119 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_manual_poll(), and vehicle_status_poll().

◆ _attitude_sp_pub

orb_advert_t FixedwingAttitudeControl::_attitude_sp_pub {nullptr}
private

attitude setpoint point

Definition at line 120 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_manual_poll().

◆ _battery_scale

float FixedwingAttitudeControl::_battery_scale {1.0f}
private

Definition at line 144 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _battery_status_sub

uORB::Subscription FixedwingAttitudeControl::_battery_status_sub {ORB_ID(battery_status)}
private

battery status subscription

Definition at line 103 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _flag_control_attitude_enabled_last

bool FixedwingAttitudeControl::_flag_control_attitude_enabled_last {false}
private

Definition at line 146 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _flaperons_applied

float FixedwingAttitudeControl::_flaperons_applied {0.0f}
private

Definition at line 138 of file FixedwingAttitudeControl.hpp.

Referenced by control_flaps(), and Run().

◆ _flaps_applied

float FixedwingAttitudeControl::_flaps_applied {0.0f}
private

Definition at line 137 of file FixedwingAttitudeControl.hpp.

Referenced by control_flaps(), and Run().

◆ _global_pos

vehicle_global_position_s FixedwingAttitudeControl::_global_pos {}
private

global position

Definition at line 131 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _global_pos_sub

uORB::Subscription FixedwingAttitudeControl::_global_pos_sub {ORB_ID(vehicle_global_position)}
private

global position subscription

Definition at line 104 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _is_tailsitter

bool FixedwingAttitudeControl::_is_tailsitter {false}
private

◆ _landed

bool FixedwingAttitudeControl::_landed {true}
private

Definition at line 142 of file FixedwingAttitudeControl.hpp.

Referenced by Run(), and vehicle_land_detected_poll().

◆ _loop_perf

perf_counter_t FixedwingAttitudeControl::_loop_perf
private

loop performance counter

Definition at line 135 of file FixedwingAttitudeControl.hpp.

Referenced by print_status(), Run(), and ~FixedwingAttitudeControl().

◆ _manual

manual_control_setpoint_s FixedwingAttitudeControl::_manual {}
private

r/c channel data

Definition at line 127 of file FixedwingAttitudeControl.hpp.

Referenced by control_flaps(), Run(), and vehicle_manual_poll().

◆ _manual_sub

uORB::Subscription FixedwingAttitudeControl::_manual_sub {ORB_ID(manual_control_setpoint)}
private

notification of manual control updates

Definition at line 105 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_manual_poll().

◆ _parameter_update_sub

uORB::Subscription FixedwingAttitudeControl::_parameter_update_sub {ORB_ID(parameter_update)}
private

notification of parameter updates

Definition at line 106 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _pitch_ctrl

ECL_PitchController FixedwingAttitudeControl::_pitch_ctrl
private

Definition at line 221 of file FixedwingAttitudeControl.hpp.

Referenced by FixedwingAttitudeControl(), parameters_update(), and Run().

◆ _rate_ctrl_status_pub

uORB::PublicationMulti<rate_ctrl_status_s> FixedwingAttitudeControl::_rate_ctrl_status_pub {ORB_ID(rate_ctrl_status)}
private

rate controller status publication

Definition at line 117 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _rate_sp_pub

uORB::Publication<vehicle_rates_setpoint_s> FixedwingAttitudeControl::_rate_sp_pub {ORB_ID(vehicle_rates_setpoint)}
private

rate setpoint publication

Definition at line 116 of file FixedwingAttitudeControl.hpp.

Referenced by Run(), and vehicle_manual_poll().

◆ _rates_sp

vehicle_rates_setpoint_s FixedwingAttitudeControl::_rates_sp {}
private

◆ _rates_sp_sub

uORB::Subscription FixedwingAttitudeControl::_rates_sp_sub {ORB_ID(vehicle_rates_setpoint)}
private

vehicle rates setpoint

Definition at line 107 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_rates_setpoint_poll().

◆ _vcontrol_mode

vehicle_control_mode_s FixedwingAttitudeControl::_vcontrol_mode {}
private

vehicle control mode

Definition at line 130 of file FixedwingAttitudeControl.hpp.

Referenced by control_flaps(), Run(), vehicle_control_mode_poll(), and vehicle_manual_poll().

◆ _vcontrol_mode_sub

uORB::Subscription FixedwingAttitudeControl::_vcontrol_mode_sub {ORB_ID(vehicle_control_mode)}
private

vehicle status subscription

Definition at line 108 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_control_mode_poll().

◆ _vehicle_land_detected_sub

uORB::Subscription FixedwingAttitudeControl::_vehicle_land_detected_sub {ORB_ID(vehicle_land_detected)}
private

vehicle land detected subscription

Definition at line 109 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_land_detected_poll().

◆ _vehicle_rates_sub

uORB::Subscription FixedwingAttitudeControl::_vehicle_rates_sub {ORB_ID(vehicle_angular_velocity)}
private

Definition at line 111 of file FixedwingAttitudeControl.hpp.

Referenced by Run().

◆ _vehicle_status

vehicle_status_s FixedwingAttitudeControl::_vehicle_status {}
private

◆ _vehicle_status_sub

uORB::Subscription FixedwingAttitudeControl::_vehicle_status_sub {ORB_ID(vehicle_status)}
private

vehicle status subscription

Definition at line 110 of file FixedwingAttitudeControl.hpp.

Referenced by vehicle_status_poll().

◆ _wheel_ctrl

ECL_WheelController FixedwingAttitudeControl::_wheel_ctrl
private

Definition at line 223 of file FixedwingAttitudeControl.hpp.

Referenced by parameters_update(), and Run().

◆ _yaw_ctrl

ECL_YawController FixedwingAttitudeControl::_yaw_ctrl
private

Definition at line 222 of file FixedwingAttitudeControl.hpp.

Referenced by FixedwingAttitudeControl(), parameters_update(), and Run().


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