PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <standard.h>
Public Member Functions | |
Standard (VtolAttitudeControl *_att_controller) | |
~Standard () 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 | update_mc_state () override |
Update multicopter state. More... | |
void | fill_actuator_outputs () override |
Prepare message to acutators with data from mc and fw attitude controllers. 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 | |
VtolType & | operator= (const VtolType &)=delete |
virtual | ~VtolType ()=default |
bool | init () |
Initialise. 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_TO_FW, vtol_mode::TRANSITION_TO_MC, vtol_mode::FW_MODE } |
Private Member Functions | |
void | parameters_update () override |
Private Attributes | |
struct { | |
float pusher_ramp_dt | |
float back_trans_ramp | |
float down_pitch_max | |
float forward_thrust_scale | |
float pitch_setpoint_offset | |
float reverse_output | |
float reverse_delay | |
} | _params_standard |
struct { | |
param_t pusher_ramp_dt | |
param_t back_trans_ramp | |
param_t down_pitch_max | |
param_t forward_thrust_scale | |
param_t pitch_setpoint_offset | |
param_t reverse_output | |
param_t reverse_delay | |
} | _params_handles_standard |
struct { | |
vtol_mode flight_mode | |
hrt_abstime transition_start | |
} | _vtol_schedule |
float | _pusher_throttle {0.0f} |
float | _reverse_output {0.0f} |
float | _airspeed_trans_blend_margin {0.0f} |
Definition at line 52 of file standard.h.
|
strongprivate |
Enumerator | |
---|---|
MC_MODE | |
TRANSITION_TO_FW | |
TRANSITION_TO_MC | |
FW_MODE |
Definition at line 89 of file standard.h.
Standard::Standard | ( | VtolAttitudeControl * | _att_controller | ) |
Definition at line 51 of file standard.cpp.
References VtolType::_mc_pitch_weight, VtolType::_mc_roll_weight, VtolType::_mc_throttle_weight, VtolType::_mc_yaw_weight, _params_handles_standard, VtolType::_pusher_active, _vtol_schedule, MC_MODE, and param_find().
|
overridedefault |
|
overridevirtual |
Prepare message to acutators with data from mc and fw attitude controllers.
An mc attitude weighting will determine what proportion of control should be applied to each of the control groups (mc and fw).
Implements VtolType.
Definition at line 409 of file standard.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_throttle_weight, VtolType::_mc_yaw_weight, VtolType::_params, _pusher_throttle, _reverse_output, _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.
|
overrideprivatevirtual |
Implements VtolType.
Definition at line 73 of file standard.cpp.
References _airspeed_trans_blend_margin, VtolType::_params, _params_handles_standard, _params_standard, Params::airspeed_blend, Params::back_trans_duration, math::constrain(), f(), param_get(), math::radians(), and Params::transition_airspeed.
|
overridevirtual |
Update fixed wing state.
Reimplemented from VtolType.
Definition at line 400 of file standard.cpp.
References VtolType::update_fw_state().
|
overridevirtual |
Update multicopter state.
Reimplemented from VtolType.
Definition at line 324 of file standard.cpp.
References VtolType::_attc, _params_standard, _pusher_throttle, VtolType::_v_att, VtolType::_v_att_sp, VtolType::_v_control_mode, matrix::Matrix< Type, M, N >::copyTo(), position_setpoint_triplet_s::current, f(), vehicle_control_mode_s::flag_control_position_enabled, FLT_EPSILON, VtolAttitudeControl::get_pos_sp_triplet(), VtolAttitudeControl::get_vtol_vehicle_status(), matrix::Vector< Type, M >::normalize(), vehicle_attitude_setpoint_s::pitch_body, vehicle_attitude_s::q, vehicle_attitude_setpoint_s::q_d, vehicle_attitude_setpoint_s::q_d_valid, vehicle_attitude_setpoint_s::roll_body, position_setpoint_s::type, VtolType::update_mc_state(), position_setpoint_s::valid, vtol_vehicle_status_s::vtol_transition_failsafe, and matrix::wrap_pi().
|
overridevirtual |
Update transition state.
Implements VtolType.
Definition at line 236 of file standard.cpp.
References _airspeed_trans_blend_margin, VtolType::_airspeed_validated, VtolType::_attc, VtolType::_mc_pitch_weight, VtolType::_mc_roll_weight, VtolType::_mc_throttle_weight, VtolType::_mc_virtual_att_sp, VtolType::_mc_yaw_weight, VtolType::_motor_state, VtolType::_params, _params_standard, _pusher_throttle, VtolType::_v_att_sp, _vtol_schedule, VtolAttitudeControl::abort_front_transition(), Params::airspeed_blend, Params::airspeed_disabled, Params::back_trans_throttle, math::constrain(), matrix::Matrix< Type, M, N >::copyTo(), ENABLED, airspeed_validated_s::equivalent_airspeed_m_s, f(), FLT_EPSILON, Params::front_trans_throttle, Params::front_trans_time_min, Params::front_trans_timeout, hrt_absolute_time(), vehicle_attitude_setpoint_s::pitch_body, vehicle_attitude_setpoint_s::q_d, vehicle_attitude_setpoint_s::q_d_valid, vehicle_attitude_setpoint_s::roll_body, VtolType::set_motor_state(), TRANSITION_TO_FW, TRANSITION_TO_MC, VtolType::update_transition_state(), and vehicle_attitude_setpoint_s::yaw_body.
|
overridevirtual |
Update vtol state.
Implements VtolType.
Definition at line 108 of file standard.cpp.
References VtolType::_airspeed_validated, VtolType::_attc, VtolType::_local_pos, VtolType::_mc_pitch_weight, VtolType::_mc_roll_weight, VtolType::_mc_throttle_weight, VtolType::_mc_yaw_weight, VtolType::_params, _params_standard, _pusher_throttle, _reverse_output, VtolType::_trans_finished_ts, VtolType::_v_att, VtolType::_vtol_mode, _vtol_schedule, VtolType::_vtol_vehicle_status, Params::airspeed_disabled, Params::back_trans_duration, VtolType::can_transition_on_ground(), airspeed_validated_s::equivalent_airspeed_m_s, f(), FIXED_WING, Params::front_trans_time_min, FW_MODE, hrt_absolute_time(), VtolAttitudeControl::is_fixed_wing_requested(), MC_MODE, vehicle_attitude_s::q, ROTARY_WING, Params::transition_airspeed, TRANSITION_TO_FW, TRANSITION_TO_FW, TRANSITION_TO_MC, TRANSITION_TO_MC, vehicle_local_position_s::v_xy_valid, vtol_vehicle_status_s::vtol_transition_failsafe, vehicle_local_position_s::vx, vehicle_local_position_s::vy, and vehicle_local_position_s::vz.
|
overridevirtual |
Special handling opportunity for the time right after transition to FW before TECS is running.
Reimplemented from VtolType.
Definition at line 486 of file standard.cpp.
References _pusher_throttle, VtolType::_v_att_sp, and vehicle_attitude_setpoint_s::thrust_body.
|
private |
Definition at line 103 of file standard.h.
Referenced by parameters_update(), and update_transition_state().
struct { ... } Standard::_params_handles_standard |
Referenced by parameters_update(), and Standard().
struct { ... } Standard::_params_standard |
Referenced by parameters_update(), update_mc_state(), update_transition_state(), and update_vtol_state().
|
private |
Definition at line 101 of file standard.h.
Referenced by fill_actuator_outputs(), update_mc_state(), update_transition_state(), update_vtol_state(), and waiting_on_tecs().
|
private |
Definition at line 102 of file standard.h.
Referenced by fill_actuator_outputs(), and update_vtol_state().
struct { ... } Standard::_vtol_schedule |
Referenced by fill_actuator_outputs(), Standard(), update_transition_state(), and update_vtol_state().
float Standard::back_trans_ramp |
Definition at line 71 of file standard.h.
param_t Standard::back_trans_ramp |
Definition at line 81 of file standard.h.
float Standard::down_pitch_max |
Definition at line 72 of file standard.h.
param_t Standard::down_pitch_max |
Definition at line 82 of file standard.h.
vtol_mode Standard::flight_mode |
Definition at line 97 of file standard.h.
float Standard::forward_thrust_scale |
Definition at line 73 of file standard.h.
param_t Standard::forward_thrust_scale |
Definition at line 83 of file standard.h.
float Standard::pitch_setpoint_offset |
Definition at line 74 of file standard.h.
param_t Standard::pitch_setpoint_offset |
Definition at line 84 of file standard.h.
float Standard::pusher_ramp_dt |
Definition at line 70 of file standard.h.
param_t Standard::pusher_ramp_dt |
Definition at line 80 of file standard.h.
float Standard::reverse_delay |
Definition at line 76 of file standard.h.
param_t Standard::reverse_delay |
Definition at line 86 of file standard.h.
float Standard::reverse_output |
Definition at line 75 of file standard.h.
param_t Standard::reverse_output |
Definition at line 85 of file standard.h.
hrt_abstime Standard::transition_start |
Definition at line 98 of file standard.h.