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

#include <mc_att_control.hpp>

Inheritance diagram for MulticopterAttitudeControl:
Collaboration diagram for MulticopterAttitudeControl:

Classes

struct  _manual_control_sp
 manual control setpoint More...
 
struct  _v_att
 vehicle attitude More...
 
struct  _v_att_sp
 vehicle attitude setpoint More...
 
struct  _v_control_mode
 vehicle control mode More...
 
struct  _v_rates_sp
 vehicle rates setpoint More...
 
struct  _vehicle_land_detected
 
struct  _vehicle_status
 vehicle status More...
 

Public Member Functions

 MulticopterAttitudeControl ()
 
virtual ~MulticopterAttitudeControl ()
 
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

void parameters_updated ()
 initialize some vectors/matrices from parameters More...
 
void vehicle_status_poll ()
 
void publish_rates_setpoint ()
 
float throttle_curve (float throttle_stick_input)
 
void generate_attitude_setpoint (float dt, bool reset_yaw_sp)
 Generate & publish an attitude setpoint from stick inputs. More...
 
void control_attitude ()
 Attitude controller. More...
 
 DEFINE_PARAMETERS ((ParamFloat< px4::params::MC_ROLL_P >) _param_mc_roll_p,(ParamFloat< px4::params::MC_PITCH_P >) _param_mc_pitch_p,(ParamFloat< px4::params::MC_YAW_P >) _param_mc_yaw_p,(ParamFloat< px4::params::MC_ROLLRATE_MAX >) _param_mc_rollrate_max,(ParamFloat< px4::params::MC_PITCHRATE_MAX >) _param_mc_pitchrate_max,(ParamFloat< px4::params::MC_YAWRATE_MAX >) _param_mc_yawrate_max,(ParamFloat< px4::params::MPC_MAN_Y_MAX >) _param_mpc_man_y_max,(ParamFloat< px4::params::MC_RATT_TH >) _param_mc_ratt_th,(ParamFloat< px4::params::MPC_MAN_TILT_MAX >) _param_mpc_man_tilt_max,(ParamFloat< px4::params::MPC_MANTHR_MIN >) _param_mpc_manthr_min,(ParamFloat< px4::params::MPC_THR_MAX >) _param_mpc_thr_max,(ParamFloat< px4::params::MPC_THR_HOVER >) _param_mpc_thr_hover,(ParamInt< px4::params::MPC_THR_CURVE >) _param_mpc_thr_curve,(ParamInt< px4::params::MC_AIRMODE >) _param_mc_airmode) bool _is_tailsitter
 

Private Attributes

AttitudeControl _attitude_control
 class for attitude control calculations More...
 
uORB::Subscription _v_att_sp_sub {ORB_ID(vehicle_attitude_setpoint)}
 vehicle attitude setpoint subscription More...
 
uORB::Subscription _v_rates_sp_sub {ORB_ID(vehicle_rates_setpoint)}
 vehicle rates setpoint subscription More...
 
uORB::Subscription _v_control_mode_sub {ORB_ID(vehicle_control_mode)}
 vehicle control mode subscription More...
 
uORB::Subscription _params_sub {ORB_ID(parameter_update)}
 parameter updates subscription More...
 
uORB::Subscription _manual_control_sp_sub {ORB_ID(manual_control_setpoint)}
 manual control setpoint subscription More...
 
uORB::Subscription _vehicle_status_sub {ORB_ID(vehicle_status)}
 vehicle status subscription More...
 
uORB::Subscription _vehicle_land_detected_sub {ORB_ID(vehicle_land_detected)}
 vehicle land detected subscription More...
 
uORB::SubscriptionCallbackWorkItem _vehicle_attitude_sub {this, ORB_ID(vehicle_attitude)}
 
uORB::Publication< vehicle_rates_setpoint_s_v_rates_sp_pub {ORB_ID(vehicle_rates_setpoint)}
 rate setpoint publication More...
 
orb_advert_t _vehicle_attitude_setpoint_pub {nullptr}
 
orb_id_t _attitude_sp_id {nullptr}
 pointer to correct attitude setpoint uORB metadata structure More...
 
perf_counter_t _loop_perf
 loop duration performance counter More...
 
matrix::Vector3f _rates_sp
 angular rates setpoint More...
 
float _man_yaw_sp {0.f}
 current yaw setpoint in manual mode More...
 
hrt_abstime _last_run {0}
 
bool _reset_yaw_sp {true}
 
float _man_tilt_max
 maximum tilt allowed for manual flight [rad] More...
 

Detailed Description

Definition at line 65 of file mc_att_control.hpp.

Constructor & Destructor Documentation

◆ MulticopterAttitudeControl()

MulticopterAttitudeControl::MulticopterAttitudeControl ( )

Definition at line 54 of file mc_att_control_main.cpp.

References parameters_updated().

Referenced by task_spawn().

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

◆ ~MulticopterAttitudeControl()

MulticopterAttitudeControl::~MulticopterAttitudeControl ( )
virtual

Definition at line 68 of file mc_att_control_main.cpp.

References _loop_perf, and perf_free().

Here is the call graph for this function:

Member Function Documentation

◆ control_attitude()

void MulticopterAttitudeControl::control_attitude ( )
private

Attitude controller.

Input: 'vehicle_attitude_setpoint' topics (depending on mode) Output: '_rates_sp' vector

Definition at line 247 of file mc_att_control_main.cpp.

References _attitude_control, _rates_sp, _v_att_sp_sub, AttitudeControl::update(), and uORB::Subscription::update().

Referenced by Run().

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

◆ custom_command()

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

Definition at line 398 of file mc_att_control_main.cpp.

References print_usage().

Here is the call graph for this function:

◆ DEFINE_PARAMETERS()

MulticopterAttitudeControl::DEFINE_PARAMETERS ( (ParamFloat< px4::params::MC_ROLL_P >)  _param_mc_roll_p,
(ParamFloat< px4::params::MC_PITCH_P >)  _param_mc_pitch_p,
(ParamFloat< px4::params::MC_YAW_P >)  _param_mc_yaw_p,
(ParamFloat< px4::params::MC_ROLLRATE_MAX >)  _param_mc_rollrate_max,
(ParamFloat< px4::params::MC_PITCHRATE_MAX >)  _param_mc_pitchrate_max,
(ParamFloat< px4::params::MC_YAWRATE_MAX >)  _param_mc_yawrate_max,
(ParamFloat< px4::params::MPC_MAN_Y_MAX >)  _param_mpc_man_y_max,
(ParamFloat< px4::params::MC_RATT_TH >)  _param_mc_ratt_th,
(ParamFloat< px4::params::MPC_MAN_TILT_MAX >)  _param_mpc_man_tilt_max,
(ParamFloat< px4::params::MPC_MANTHR_MIN >)  _param_mpc_manthr_min,
(ParamFloat< px4::params::MPC_THR_MAX >)  _param_mpc_thr_max,
(ParamFloat< px4::params::MPC_THR_HOVER >)  _param_mpc_thr_hover,
(ParamInt< px4::params::MPC_THR_CURVE >)  _param_mpc_thr_curve,
(ParamInt< px4::params::MC_AIRMODE >)  _param_mc_airmode 
)
inlineprivate
Parameters
_param_mpc_man_y_maxscaling factor from stick to yaw rate
_param_mpc_man_tilt_maxmaximum tilt allowed for manual flight
_param_mpc_manthr_minminimum throttle for stabilized
_param_mpc_thr_maxmaximum throttle for stabilized
_param_mpc_thr_hoverthrottle at which vehicle is at hover equilibrium
_param_mpc_thr_curvethrottle curve behavior

Definition at line 148 of file mc_att_control.hpp.

◆ generate_attitude_setpoint()

void MulticopterAttitudeControl::generate_attitude_setpoint ( float  dt,
bool  reset_yaw_sp 
)
private

Generate & publish an attitude setpoint from stick inputs.

Definition at line 144 of file mc_att_control_main.cpp.

References _attitude_sp_id, _man_tilt_max, _man_yaw_sp, _vehicle_attitude_setpoint_pub, matrix::Matrix< Type, M, N >::copyTo(), f(), hrt_absolute_time(), matrix::Vector< Type, M >::norm(), ORB_PRIO_DEFAULT, orb_publish_auto(), math::radians(), Mixer::roll_pitch_yaw, throttle_curve(), and matrix::wrap_pi().

Referenced by Run().

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

◆ init()

bool MulticopterAttitudeControl::init ( )

Definition at line 74 of file mc_att_control_main.cpp.

References _vehicle_attitude_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_updated()

void MulticopterAttitudeControl::parameters_updated ( )
private

initialize some vectors/matrices from parameters

Definition at line 85 of file mc_att_control_main.cpp.

References _attitude_control, _man_tilt_max, math::radians(), AttitudeControl::setProportionalGain(), and AttitudeControl::setRateLimit().

Referenced by MulticopterAttitudeControl(), and Run().

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

◆ print_status()

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

Definition at line 389 of file mc_att_control_main.cpp.

References _loop_perf, and perf_print_counter().

Here is the call graph for this function:

◆ print_usage()

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

Definition at line 403 of file mc_att_control_main.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ publish_rates_setpoint()

void MulticopterAttitudeControl::publish_rates_setpoint ( )
private

Definition at line 254 of file mc_att_control_main.cpp.

References _rates_sp, _v_rates_sp_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and vehicle_rates_setpoint_s::roll.

Referenced by Run().

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

◆ Run()

◆ task_spawn()

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

Definition at line 366 of file mc_att_control_main.cpp.

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

Here is the call graph for this function:

◆ throttle_curve()

float MulticopterAttitudeControl::throttle_curve ( float  throttle_stick_input)
private

Definition at line 122 of file mc_att_control_main.cpp.

References f().

Referenced by generate_attitude_setpoint().

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

◆ vehicle_status_poll()

void MulticopterAttitudeControl::vehicle_status_poll ( )
private

Definition at line 99 of file mc_att_control_main.cpp.

References _attitude_sp_id, _vehicle_status_sub, ORB_ID, param_find(), param_get(), TAILSITTER, and uORB::Subscription::update().

Referenced by Run().

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

Member Data Documentation

◆ _attitude_control

AttitudeControl MulticopterAttitudeControl::_attitude_control
private

class for attitude control calculations

Definition at line 112 of file mc_att_control.hpp.

Referenced by control_attitude(), and parameters_updated().

◆ _attitude_sp_id

orb_id_t MulticopterAttitudeControl::_attitude_sp_id {nullptr}
private

pointer to correct attitude setpoint uORB metadata structure

Definition at line 128 of file mc_att_control.hpp.

Referenced by generate_attitude_setpoint(), and vehicle_status_poll().

◆ _last_run

hrt_abstime MulticopterAttitudeControl::_last_run {0}
private

Definition at line 144 of file mc_att_control.hpp.

Referenced by Run().

◆ _loop_perf

perf_counter_t MulticopterAttitudeControl::_loop_perf
private

loop duration performance counter

Definition at line 138 of file mc_att_control.hpp.

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

◆ _man_tilt_max

float MulticopterAttitudeControl::_man_tilt_max
private

maximum tilt allowed for manual flight [rad]

Definition at line 172 of file mc_att_control.hpp.

Referenced by generate_attitude_setpoint(), and parameters_updated().

◆ _man_yaw_sp

float MulticopterAttitudeControl::_man_yaw_sp {0.f}
private

current yaw setpoint in manual mode

Definition at line 142 of file mc_att_control.hpp.

Referenced by generate_attitude_setpoint(), and Run().

◆ _manual_control_sp_sub

uORB::Subscription MulticopterAttitudeControl::_manual_control_sp_sub {ORB_ID(manual_control_setpoint)}
private

manual control setpoint subscription

Definition at line 118 of file mc_att_control.hpp.

Referenced by Run().

◆ _params_sub

uORB::Subscription MulticopterAttitudeControl::_params_sub {ORB_ID(parameter_update)}
private

parameter updates subscription

Definition at line 117 of file mc_att_control.hpp.

Referenced by Run().

◆ _rates_sp

matrix::Vector3f MulticopterAttitudeControl::_rates_sp
private

angular rates setpoint

Definition at line 140 of file mc_att_control.hpp.

Referenced by control_attitude(), publish_rates_setpoint(), and Run().

◆ _reset_yaw_sp

bool MulticopterAttitudeControl::_reset_yaw_sp {true}
private

Definition at line 146 of file mc_att_control.hpp.

Referenced by Run().

◆ _v_att_sp_sub

uORB::Subscription MulticopterAttitudeControl::_v_att_sp_sub {ORB_ID(vehicle_attitude_setpoint)}
private

vehicle attitude setpoint subscription

Definition at line 114 of file mc_att_control.hpp.

Referenced by control_attitude().

◆ _v_control_mode_sub

uORB::Subscription MulticopterAttitudeControl::_v_control_mode_sub {ORB_ID(vehicle_control_mode)}
private

vehicle control mode subscription

Definition at line 116 of file mc_att_control.hpp.

Referenced by Run().

◆ _v_rates_sp_pub

uORB::Publication<vehicle_rates_setpoint_s> MulticopterAttitudeControl::_v_rates_sp_pub {ORB_ID(vehicle_rates_setpoint)}
private

rate setpoint publication

Definition at line 124 of file mc_att_control.hpp.

Referenced by publish_rates_setpoint().

◆ _v_rates_sp_sub

uORB::Subscription MulticopterAttitudeControl::_v_rates_sp_sub {ORB_ID(vehicle_rates_setpoint)}
private

vehicle rates setpoint subscription

Definition at line 115 of file mc_att_control.hpp.

Referenced by Run().

◆ _vehicle_attitude_setpoint_pub

orb_advert_t MulticopterAttitudeControl::_vehicle_attitude_setpoint_pub {nullptr}
private

Definition at line 126 of file mc_att_control.hpp.

Referenced by generate_attitude_setpoint().

◆ _vehicle_attitude_sub

uORB::SubscriptionCallbackWorkItem MulticopterAttitudeControl::_vehicle_attitude_sub {this, ORB_ID(vehicle_attitude)}
private

Definition at line 122 of file mc_att_control.hpp.

Referenced by init(), and Run().

◆ _vehicle_land_detected_sub

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

vehicle land detected subscription

Definition at line 120 of file mc_att_control.hpp.

Referenced by Run().

◆ _vehicle_status_sub

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

vehicle status subscription

Definition at line 119 of file mc_att_control.hpp.

Referenced by vehicle_status_poll().


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