PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <FixedwingPositionControl.hpp>
Public Member Functions | |
FixedwingPositionControl () | |
~FixedwingPositionControl () override | |
void | Run () override |
bool | init () |
int | print_status () override |
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 Types | |
enum | FW_POSCTRL_MODE { FW_POSCTRL_MODE_AUTO, FW_POSCTRL_MODE_POSITION, FW_POSCTRL_MODE_ALTITUDE, FW_POSCTRL_MODE_OTHER } |
Private Member Functions | |
DEFINE_PARAMETERS ((ParamFloat< px4::params::FW_GND_SPD_MIN >) _groundspeed_min) int parameters_update() | |
void | airspeed_poll () |
void | control_update () |
void | vehicle_attitude_poll () |
void | vehicle_command_poll () |
void | vehicle_control_mode_poll () |
void | vehicle_status_poll () |
void | status_publish () |
void | landing_status_publish () |
void | tecs_status_publish () |
void | abort_landing (bool abort) |
void | get_waypoint_heading_distance (float heading, position_setpoint_s &waypoint_prev, position_setpoint_s &waypoint_next, bool flag_init) |
Get a new waypoint based on heading and distance from current position. More... | |
float | get_terrain_altitude_takeoff (float takeoff_alt, const vehicle_global_position_s &global_pos) |
Return the terrain estimate during takeoff or takeoff_alt if terrain estimate is not available. More... | |
bool | in_takeoff_situation () |
Check if we are in a takeoff situation. More... | |
void | do_takeoff_help (float *hold_altitude, float *pitch_limit_min) |
Do takeoff help when in altitude controlled modes. More... | |
bool | update_desired_altitude (float dt) |
Update desired altitude base on user pitch stick input. More... | |
bool | control_position (const Vector2f &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr, const position_setpoint_s &pos_sp_next) |
void | control_takeoff (const Vector2f &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) |
void | control_landing (const Vector2f &curr_pos, const Vector2f &ground_speed, const position_setpoint_s &pos_sp_prev, const position_setpoint_s &pos_sp_curr) |
float | get_tecs_pitch () |
float | get_tecs_thrust () |
float | get_demanded_airspeed () |
float | calculate_target_airspeed (float airspeed_demand, const Vector2f &ground_speed) |
void | handle_command () |
Handle incoming vehicle commands. More... | |
void | reset_takeoff_state (bool force=false) |
void | reset_landing_state () |
void | tecs_update_pitch_throttle (float alt_sp, float airspeed_sp, float pitch_min_rad, float pitch_max_rad, float throttle_min, float throttle_max, float throttle_cruise, bool climbout_mode, float climbout_pitch_min_rad, uint8_t mode=tecs_status_s::TECS_MODE_NORMAL) |
Definition at line 128 of file FixedwingPositionControl.hpp.
|
private |
Enumerator | |
---|---|
FW_POSCTRL_MODE_AUTO | |
FW_POSCTRL_MODE_POSITION | |
FW_POSCTRL_MODE_ALTITUDE | |
FW_POSCTRL_MODE_OTHER |
Definition at line 263 of file FixedwingPositionControl.hpp.
FixedwingPositionControl::FixedwingPositionControl | ( | ) |
Definition at line 36 of file FixedwingPositionControl.cpp.
References _global_pos_sub, _parameter_handles, _parameters, param_find(), PARAM_INVALID, mpu9x50::parameters_update(), and uORB::SubscriptionInterval::set_interval_ms().
Referenced by task_spawn().
|
override |
Definition at line 112 of file FixedwingPositionControl.cpp.
References _loop_perf, and perf_free().
|
private |
Definition at line 576 of file FixedwingPositionControl.cpp.
References _land_abort, _mavlink_log_pub, landing_status_publish(), and mavlink_log_critical.
Referenced by control_landing(), control_position(), handle_command(), and reset_landing_state().
|
private |
Definition at line 358 of file FixedwingPositionControl.cpp.
References _airspeed, _airspeed_last_valid, _airspeed_valid, _airspeed_validated_sub, _eas2tas, _parameters, _tecs, math::constrain(), TECS::enable_airspeed(), airspeed_validated_s::equivalent_airspeed_m_s, uORB::SubscriptionData< T >::get(), hrt_elapsed_time(), airspeed_validated_s::timestamp, airspeed_validated_s::true_airspeed_m_s, and uORB::SubscriptionData< T >::update().
Referenced by Run().
|
private |
Definition at line 437 of file FixedwingPositionControl.cpp.
References _airspeed_valid, _att_sp, _l1_control, _parameters, _R_nb, ECL_L1_Pos_Controller::circle_mode(), math::constrain(), math::max(), and vehicle_attitude_setpoint_s::roll_body.
Referenced by control_landing(), control_position(), and control_takeoff().
|
private |
Definition at line 1353 of file FixedwingPositionControl.cpp.
References _att_sp, _flare_curve_alt_rel_last, _flare_height, _flare_pitch_sp, _global_pos, _l1_control, _land_motor_lim, _land_noreturn_horizontal, _land_noreturn_vertical, _land_onslope, _land_stayonground, _landingslope, _mavlink_log_pub, _parameters, _t_alt_prev_valid, _target_bearing, _tecs, _time_last_t_alt, _time_started_landing, _yaw, abort_landing(), vehicle_global_position_s::alt, position_setpoint_s::alt, vehicle_attitude_setpoint_s::apply_flaps, calculate_target_airspeed(), math::constrain(), create_waypoint_from_line_and_dist(), f(), Landingslope::flare_length(), Landingslope::flare_relative_alt(), vehicle_attitude_setpoint_s::fw_control_yaw, get_bearing_to_next_waypoint(), get_distance_to_next_waypoint(), ECL_L1_Pos_Controller::get_roll_setpoint(), Landingslope::getFlareCurveRelativeAltitudeSave(), Landingslope::getLandingSlopeRelativeAltitudeSave(), hrt_absolute_time(), hrt_elapsed_time(), position_setpoint_s::lat, position_setpoint_s::lon, mavlink_log_info, math::min(), Landingslope::motor_lim_relative_alt(), ECL_L1_Pos_Controller::nav_bearing(), ECL_L1_Pos_Controller::navigate_heading(), ECL_L1_Pos_Controller::navigate_waypoints(), vehicle_attitude_setpoint_s::pitch_body, math::radians(), reset_landing_state(), vehicle_attitude_setpoint_s::roll_body, TECS::set_time_const_throt(), T_ALT_TIMEOUT, tecs_update_pitch_throttle(), vehicle_global_position_s::terrain_alt, vehicle_global_position_s::terrain_alt_valid, throttle_max, position_setpoint_s::valid, vehicle_global_position_s::vel_d, matrix::wrap_pi(), and vehicle_attitude_setpoint_s::yaw_body.
Referenced by control_position().
|
private |
Definition at line 728 of file FixedwingPositionControl.cpp.
References _airspeed, _airspeed_valid, _att_sp, _control_mode, _control_position_last_called, _global_pos, _hdg_hold_curr_wp, _hdg_hold_enabled, _hdg_hold_prev_wp, _hdg_hold_yaw, _hold_alt, _l1_control, _land_abort, _land_noreturn_vertical, _last_manual, _launch_detection_state, _manual, _parameters, _runway_takeoff, _takeoff_ground_alt, _tecs, _time_went_in_air, _vehicle_land_detected, _vehicle_rates_sub, _vehicle_status, _was_in_air, _yaw, _yaw_lock_engaged, abort_landing(), vehicle_global_position_s::alt, position_setpoint_s::alt, vehicle_attitude_setpoint_s::apply_flaps, calculate_target_airspeed(), ECL_L1_Pos_Controller::circle_mode(), math::constrain(), control_landing(), control_takeoff(), position_setpoint_s::cruising_speed, position_setpoint_s::cruising_throttle, do_takeoff_help(), dt, f(), vehicle_control_mode_s::flag_control_altitude_enabled, vehicle_control_mode_s::flag_control_auto_enabled, vehicle_control_mode_s::flag_control_offboard_enabled, vehicle_control_mode_s::flag_control_position_enabled, vehicle_control_mode_s::flag_control_velocity_enabled, vehicle_attitude_setpoint_s::fw_control_yaw, FW_POSCTRL_MODE_ALTITUDE, FW_POSCTRL_MODE_AUTO, FW_POSCTRL_MODE_OTHER, FW_POSCTRL_MODE_POSITION, uORB::SubscriptionData< T >::get(), get_demanded_airspeed(), get_distance_to_next_waypoint(), ECL_L1_Pos_Controller::get_roll_setpoint(), get_tecs_pitch(), get_tecs_thrust(), get_waypoint_heading_distance(), runwaytakeoff::RunwayTakeoff::getThrottle(), HDG_HOLD_MAN_INPUT_THRESH, HDG_HOLD_REACHED_DIST, HDG_HOLD_YAWRATE_THRESH, hrt_absolute_time(), hrt_elapsed_time(), in_takeoff_situation(), vehicle_status_s::in_transition_mode, vehicle_land_detected_s::landed, vehicle_global_position_s::lat, position_setpoint_s::lat, launchdetection::LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS, launchdetection::LAUNCHDETECTION_RES_NONE, position_setpoint_s::loiter_direction, position_setpoint_s::loiter_radius, loiter_radius, vehicle_global_position_s::lon, position_setpoint_s::lon, math::max(), math::min(), ECL_L1_Pos_Controller::nav_bearing(), ECL_L1_Pos_Controller::navigate_loiter(), ECL_L1_Pos_Controller::navigate_waypoints(), vehicle_attitude_setpoint_s::pitch_body, pitch_limit_min, vehicle_attitude_setpoint_s::pitch_reset_integral, manual_control_setpoint_s::r, math::radians(), reset_landing_state(), TECS::reset_state(), reset_takeoff_state(), vehicle_attitude_setpoint_s::roll_body, vehicle_attitude_setpoint_s::roll_reset_integral, runwaytakeoff::RunwayTakeoff::runwayTakeoffEnabled(), ECL_L1_Pos_Controller::set_dt(), TECS::set_speed_weight(), TECS::set_time_const_throt(), tecs_update_pitch_throttle(), throttle_max, THROTTLE_THRESH, vehicle_attitude_setpoint_s::thrust_body, position_setpoint_s::type, update_desired_altitude(), position_setpoint_s::valid, vehicle_status_s::vehicle_type, vehicle_angular_velocity_s::xyz, manual_control_setpoint_s::y, vehicle_attitude_setpoint_s::yaw_body, vehicle_attitude_setpoint_s::yaw_reset_integral, and manual_control_setpoint_s::z.
Referenced by Run().
|
private |
Definition at line 1183 of file FixedwingPositionControl.cpp.
References _airspeed, _att, _att_sp, _control_mode, _global_pos, _l1_control, _launch_detection_notify, _launch_detection_state, _launchDetector, _mavlink_log_pub, _parameters, _runway_takeoff, _takeoff_ground_alt, _vehicle_acceleration_sub, vehicle_global_position_s::alt, position_setpoint_s::alt, vehicle_attitude_setpoint_s::apply_flaps, calculate_target_airspeed(), runwaytakeoff::RunwayTakeoff::climbout(), math::constrain(), runwaytakeoff::RunwayTakeoff::controlYaw(), f(), vehicle_control_mode_s::flag_armed, vehicle_attitude_setpoint_s::fw_control_yaw, uORB::SubscriptionData< T >::get(), ECL_L1_Pos_Controller::get_roll_setpoint(), get_tecs_pitch(), get_terrain_altitude_takeoff(), launchdetection::LaunchDetector::getLaunchDetected(), runwaytakeoff::RunwayTakeoff::getMaxPitch(), runwaytakeoff::RunwayTakeoff::getMinAirspeedScaling(), runwaytakeoff::RunwayTakeoff::getMinPitch(), runwaytakeoff::RunwayTakeoff::getPitch(), launchdetection::LaunchDetector::getPitchMax(), runwaytakeoff::RunwayTakeoff::getRoll(), runwaytakeoff::RunwayTakeoff::getStartWP(), runwaytakeoff::RunwayTakeoff::getYaw(), hrt_absolute_time(), hrt_elapsed_time(), runwaytakeoff::RunwayTakeoff::init(), runwaytakeoff::RunwayTakeoff::isInitialized(), vehicle_global_position_s::lat, position_setpoint_s::lat, launchdetection::LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS, launchdetection::LAUNCHDETECTION_RES_NONE, launchdetection::LaunchDetector::launchDetectionEnabled(), vehicle_global_position_s::lon, position_setpoint_s::lon, mavlink_log_critical, mavlink_log_info, math::max(), ECL_L1_Pos_Controller::nav_bearing(), ECL_L1_Pos_Controller::navigate_waypoints(), vehicle_attitude_setpoint_s::pitch_body, position_setpoint_s::pitch_min, vehicle_attitude_setpoint_s::pitch_reset_integral, vehicle_attitude_s::q, math::radians(), launchdetection::LaunchDetector::reset(), runwaytakeoff::RunwayTakeoff::resetIntegrators(), vehicle_attitude_setpoint_s::roll_body, vehicle_attitude_setpoint_s::roll_reset_integral, runwaytakeoff::RunwayTakeoff::runwayTakeoffEnabled(), tecs_update_pitch_throttle(), launchdetection::LaunchDetector::update(), runwaytakeoff::RunwayTakeoff::update(), position_setpoint_s::valid, vehicle_acceleration_s::xyz, vehicle_attitude_setpoint_s::yaw_body, and vehicle_attitude_setpoint_s::yaw_reset_integral.
Referenced by control_position().
|
private |
|
static |
Definition at line 1968 of file FixedwingPositionControl.cpp.
References print_usage().
|
private |
|
private |
Do takeoff help when in altitude controlled modes.
hold_altitude | altitude setpoint for controller |
pitch_limit_min | minimum pitch allowed |
Definition at line 718 of file FixedwingPositionControl.cpp.
References _parameters, _takeoff_ground_alt, f(), in_takeoff_situation(), and math::radians().
Referenced by control_position().
|
private |
Definition at line 415 of file FixedwingPositionControl.cpp.
References _manual, _parameters, and manual_control_setpoint_s::z.
Referenced by control_position().
|
private |
Definition at line 1622 of file FixedwingPositionControl.cpp.
References _is_tecs_running, _tecs, and TECS::get_pitch_setpoint().
Referenced by control_position(), and control_takeoff().
|
private |
Definition at line 1633 of file FixedwingPositionControl.cpp.
References _is_tecs_running, _tecs, and TECS::get_throttle_setpoint().
Referenced by control_position().
|
private |
Return the terrain estimate during takeoff or takeoff_alt if terrain estimate is not available.
Definition at line 625 of file FixedwingPositionControl.cpp.
References vehicle_global_position_s::terrain_alt, and vehicle_global_position_s::terrain_alt_valid.
Referenced by control_takeoff().
|
private |
Get a new waypoint based on heading and distance from current position.
heading | the heading to fly to |
distance | the distance of the generated waypoint |
waypoint_prev | the waypoint at the current position |
waypoint_next | the waypoint in the heading direction |
Definition at line 588 of file FixedwingPositionControl.cpp.
References _global_pos, _hold_alt, position_setpoint_s::alt, create_waypoint_from_line_and_dist(), f(), HDG_HOLD_DIST_NEXT, HDG_HOLD_REACHED_DIST, HDG_HOLD_SET_BACK_DIST, vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, math::radians(), position_setpoint_s::valid, and waypoint_from_heading_and_distance().
Referenced by control_position().
|
private |
Handle incoming vehicle commands.
Definition at line 1644 of file FixedwingPositionControl.cpp.
References _control_mode, _pos_sp_triplet, _vehicle_command, abort_landing(), vehicle_command_s::command, position_setpoint_triplet_s::current, vehicle_control_mode_s::flag_control_auto_enabled, position_setpoint_s::type, and position_setpoint_s::valid.
Referenced by vehicle_command_poll().
|
private |
Check if we are in a takeoff situation.
Definition at line 703 of file FixedwingPositionControl.cpp.
References _global_pos, _parameters, _takeoff_ground_alt, _time_went_in_air, _vehicle_status, vehicle_global_position_s::alt, hrt_abstime, hrt_elapsed_time(), and vehicle_status_s::is_vtol.
Referenced by control_position(), and do_takeoff_help().
bool FixedwingPositionControl::init | ( | ) |
Definition at line 118 of file FixedwingPositionControl.cpp.
References _global_pos_sub, _l1_control, _landingslope, _mavlink_log_pub, _parameter_handles, _parameters, _tecs, f(), land_flare_alt_relative, land_H1_virt, land_slope_angle, land_thrust_lim_alt_relative, landing_status_publish(), mavlink_log_critical, param_get(), PARAM_INVALID, mpu9x50::parameters_update(), math::radians(), uORB::SubscriptionCallback::registerCallback(), TECS::set_height_comp_filter_omega(), TECS::set_heightrate_ff(), TECS::set_heightrate_p(), TECS::set_indicated_airspeed_max(), TECS::set_indicated_airspeed_min(), TECS::set_integrator_gain(), ECL_L1_Pos_Controller::set_l1_damping(), ECL_L1_Pos_Controller::set_l1_period(), ECL_L1_Pos_Controller::set_l1_roll_limit(), TECS::set_max_climb_rate(), TECS::set_max_sink_rate(), TECS::set_min_sink_rate(), TECS::set_pitch_damping(), ECL_L1_Pos_Controller::set_roll_slew_rate(), TECS::set_roll_throttle_compensation(), TECS::set_speed_comp_filter_omega(), TECS::set_speed_weight(), TECS::set_speedrate_p(), TECS::set_throttle_damp(), TECS::set_throttle_slewrate(), TECS::set_time_const(), TECS::set_time_const_throt(), TECS::set_vertical_accel_limit(), and Landingslope::update().
Referenced by task_spawn().
|
private |
Definition at line 560 of file FixedwingPositionControl.cpp.
References _land_abort, _landingslope, _pos_ctrl_landing_status_pub, position_controller_landing_status_s::abort_landing, position_controller_landing_status_s::flare_length, Landingslope::flare_length(), position_controller_landing_status_s::horizontal_slope_displacement, Landingslope::horizontal_slope_displacement(), hrt_absolute_time(), Landingslope::landing_slope_angle_rad(), uORB::Publication< T >::publish(), position_controller_landing_status_s::slope_angle_rad, and position_controller_landing_status_s::timestamp.
Referenced by abort_landing(), and init().
|
override |
Definition at line 1973 of file FixedwingPositionControl.cpp.
References _loop_perf, and perf_print_counter().
|
static |
Definition at line 1980 of file FixedwingPositionControl.cpp.
Referenced by custom_command().
|
private |
Definition at line 1796 of file FixedwingPositionControl.cpp.
References _land_abort, _land_motor_lim, _land_noreturn_horizontal, _land_noreturn_vertical, _land_onslope, _land_stayonground, _pos_sp_triplet, _time_last_t_alt, _time_started_landing, abort_landing(), position_setpoint_triplet_s::current, and position_setpoint_s::type.
Referenced by control_landing(), control_position(), and vehicle_control_mode_poll().
|
private |
Definition at line 1779 of file FixedwingPositionControl.cpp.
References _control_mode, _launch_detection_notify, _launch_detection_state, _launchDetector, _runway_takeoff, _vehicle_land_detected, _was_in_air, vehicle_control_mode_s::flag_armed, vehicle_land_detected_s::landed, launchdetection::LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS, launchdetection::LAUNCHDETECTION_RES_NONE, launchdetection::LaunchDetector::reset(), and runwaytakeoff::RunwayTakeoff::reset().
Referenced by control_position(), and vehicle_control_mode_poll().
|
override |
Definition at line 1658 of file FixedwingPositionControl.cpp.
References _alt_reset_counter, _att_sp, _attitude_setpoint_id, _attitude_sp_pub, _control_mode, _global_pos, _global_pos_sub, _hdg_hold_enabled, _hold_alt, _local_pos, _local_pos_sub, _loop_perf, _manual, _manual_control_sub, _parameter_update_sub, _parameters, _pos_reset_counter, _pos_sp_triplet, _pos_sp_triplet_sub, _tecs, _vehicle_acceleration_sub, _vehicle_land_detected, _vehicle_land_detected_sub, _vehicle_rates_sub, _vehicle_status, airspeed_poll(), vehicle_global_position_s::alt, position_setpoint_s::alt, vehicle_global_position_s::alt_reset_counter, math::constrain(), control_position(), uORB::Subscription::copy(), position_setpoint_triplet_s::current, vehicle_global_position_s::delta_alt, vehicle_control_mode_s::flag_control_acceleration_enabled, vehicle_control_mode_s::flag_control_altitude_enabled, vehicle_control_mode_s::flag_control_manual_enabled, vehicle_control_mode_s::flag_control_offboard_enabled, vehicle_control_mode_s::flag_control_position_enabled, vehicle_control_mode_s::flag_control_velocity_enabled, globallocalconverter_init(), globallocalconverter_initialized(), globallocalconverter_toglobal(), TECS::handle_alt_step(), hrt_absolute_time(), vehicle_status_s::in_transition_mode, vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lat_lon_reset_counter, vehicle_global_position_s::lon, position_setpoint_s::lon, position_setpoint_triplet_s::next, orb_advertise(), orb_publish(), mpu9x50::parameters_update(), perf_begin(), perf_end(), vehicle_attitude_setpoint_s::pitch_body, position_setpoint_triplet_s::previous, vehicle_attitude_setpoint_s::q_d, vehicle_attitude_setpoint_s::q_d_valid, vehicle_local_position_s::ref_alt, vehicle_local_position_s::ref_lat, vehicle_local_position_s::ref_lon, vehicle_local_position_s::ref_timestamp, vehicle_attitude_setpoint_s::roll_body, status_publish(), vehicle_attitude_setpoint_s::timestamp, uORB::SubscriptionCallback::unregisterCallback(), uORB::SubscriptionInterval::update(), uORB::Subscription::update(), uORB::SubscriptionData< T >::update(), uORB::Subscription::updated(), vehicle_attitude_poll(), vehicle_command_poll(), vehicle_control_mode_poll(), vehicle_status_poll(), vehicle_status_s::vehicle_type, VEHICLE_TYPE_FIXED_WING, vehicle_global_position_s::vel_e, vehicle_global_position_s::vel_n, position_setpoint_s::x, position_setpoint_s::y, vehicle_attitude_setpoint_s::yaw_body, and position_setpoint_s::z.
|
private |
Definition at line 536 of file FixedwingPositionControl.cpp.
References _att_sp, _global_pos, _l1_control, _pos_ctrl_status_pub, _pos_sp_triplet, position_controller_status_s::acceptance_radius, ECL_L1_Pos_Controller::crosstrack_error(), position_setpoint_triplet_s::current, f(), get_distance_to_next_waypoint(), hrt_absolute_time(), vehicle_global_position_s::lat, position_setpoint_s::lat, vehicle_global_position_s::lon, position_setpoint_s::lon, position_controller_status_s::nav_bearing, ECL_L1_Pos_Controller::nav_bearing(), position_controller_status_s::nav_pitch, position_controller_status_s::nav_roll, vehicle_attitude_setpoint_s::pitch_body, uORB::Publication< T >::publish(), vehicle_attitude_setpoint_s::roll_body, ECL_L1_Pos_Controller::switch_distance(), position_controller_status_s::target_bearing, ECL_L1_Pos_Controller::target_bearing(), position_controller_status_s::timestamp, position_controller_status_s::wp_dist, position_controller_status_s::xtrack_error, and position_controller_status_s::yaw_acceptance.
Referenced by Run().
|
static |
Definition at line 1945 of file FixedwingPositionControl.cpp.
References FixedwingPositionControl(), init(), and ll40ls::instance.
|
private |
Definition at line 487 of file FixedwingPositionControl.cpp.
References _tecs, _tecs_status_pub, tecs_status_s::airspeed_derivative, tecs_status_s::airspeed_derivative_sp, tecs_status_s::airspeed_filtered, tecs_status_s::airspeed_sp, tecs_status_s::altitude_filtered, tecs_status_s::altitude_sp, TECS::ECL_TECS_MODE_BAD_DESCENT, TECS::ECL_TECS_MODE_CLIMBOUT, TECS::ECL_TECS_MODE_NORMAL, TECS::ECL_TECS_MODE_UNDERSPEED, tecs_status_s::energy_distribution_error, tecs_status_s::energy_distribution_rate_error, tecs_status_s::height_rate, tecs_status_s::height_rate_setpoint, TECS::hgt_rate_setpoint(), TECS::hgt_setpoint_adj(), hrt_absolute_time(), tecs_status_s::mode, tecs_status_s::pitch_integ, TECS::pitch_integ_state(), uORB::Publication< T >::publish(), TECS::SEB_error(), TECS::SEB_rate_error(), TECS::speed_derivative(), TECS::STE_error(), TECS::STE_rate_error(), TECS::TAS_rate_setpoint(), TECS::TAS_setpoint_adj(), TECS::tas_state(), TECS::tecs_mode(), tecs_status_s::throttle_integ, TECS::throttle_integ_state(), tecs_status_s::timestamp, tecs_status_s::total_energy_error, tecs_status_s::total_energy_rate_error, TECS::vert_pos_state(), and TECS::vert_vel_state().
Referenced by tecs_update_pitch_throttle().
|
private |
Definition at line 1817 of file FixedwingPositionControl.cpp.
References _airspeed, _asp_after_transition, _control_mode, _eas2tas, _global_pos, _is_tecs_running, _last_tecs_update, _local_pos, _parameters, _pitch, _R_nb, _reinitialize_tecs, _sensor_baro_sub, _tecs, _vehicle_acceleration_sub, _vehicle_land_detected, _vehicle_status, _was_in_transition, vehicle_global_position_s::alt, vehicle_local_position_s::az, CONSTANTS_STD_PRESSURE_MBAR, math::constrain(), dt, vehicle_status_s::engine_failure, f(), vehicle_control_mode_s::flag_control_altitude_enabled, vehicle_control_mode_s::flag_control_auto_enabled, vehicle_control_mode_s::flag_control_offboard_enabled, vehicle_control_mode_s::flag_control_velocity_enabled, FLT_EPSILON, uORB::SubscriptionData< T >::get(), hrt_absolute_time(), hrt_elapsed_time(), vehicle_status_s::in_transition_mode, vehicle_status_s::is_vtol, vehicle_land_detected_s::landed, math::max(), TECS::reset_state(), TECS::set_detect_underspeed_enabled(), TAILSITTER, tecs_status_publish(), vehicle_global_position_s::timestamp, uORB::Subscription::update(), TECS::update_pitch_throttle(), TECS::update_vehicle_state_estimates(), vehicle_local_position_s::v_z_valid, vehicle_status_s::vehicle_type, vehicle_local_position_s::vz, and vehicle_acceleration_s::xyz.
Referenced by control_landing(), control_position(), and control_takeoff().
|
private |
Update desired altitude base on user pitch stick input.
dt | Time step |
Definition at line 636 of file FixedwingPositionControl.cpp.
References _althold_epv, _global_pos, _hold_alt, _manual, _parameters, _vehicle_status, _was_in_deadband, vehicle_global_position_s::alt, ALTHOLD_EPV_RESET_THRESH, dt, vehicle_global_position_s::epv, vehicle_status_s::in_transition_mode, vehicle_status_s::is_vtol, MANUAL_THROTTLE_CLIMBOUT_THRESH, vehicle_status_s::vehicle_type, and manual_control_setpoint_s::x.
Referenced by control_position().
|
private |
Definition at line 394 of file FixedwingPositionControl.cpp.
References _att, _parameters, _pitch, _R_nb, _roll, _vehicle_attitude_sub, _vehicle_status, _yaw, vehicle_status_s::is_vtol, vehicle_attitude_s::q, TAILSITTER, and uORB::Subscription::update().
Referenced by Run().
|
private |
Definition at line 328 of file FixedwingPositionControl.cpp.
References _vehicle_command, _vehicle_command_sub, uORB::Subscription::copy(), handle_command(), and uORB::Subscription::updated().
Referenced by Run().
|
private |
Definition at line 311 of file FixedwingPositionControl.cpp.
References _control_mode, _control_mode_sub, uORB::Subscription::copy(), vehicle_control_mode_s::flag_armed, reset_landing_state(), reset_takeoff_state(), and uORB::Subscription::updated().
Referenced by Run().
|
private |
Definition at line 337 of file FixedwingPositionControl.cpp.
References _attitude_setpoint_id, _parameter_handles, _vehicle_status, _vehicle_status_sub, vehicle_status_s::is_vtol, ORB_ID, param_find(), mpu9x50::parameters_update(), and uORB::Subscription::update().
Referenced by Run().
|
private |
Definition at line 239 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll(), control_position(), control_takeoff(), and tecs_update_pitch_throttle().
|
private |
last time airspeed was received. Used to detect timeouts.
Definition at line 238 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll().
|
private |
flag if a valid airspeed estimate exists
Definition at line 237 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll(), calculate_target_airspeed(), and control_position().
|
private |
Definition at line 186 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll().
|
private |
captures the number of times the estimator has reset the altitude state
Definition at line 258 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
the position estimate accuracy when engaging alt hold
Definition at line 196 of file FixedwingPositionControl.hpp.
Referenced by update_desired_altitude().
|
private |
Definition at line 253 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle().
|
private |
vehicle attitude setpoint
Definition at line 177 of file FixedwingPositionControl.hpp.
Referenced by control_takeoff(), and vehicle_attitude_poll().
|
private |
vehicle attitude setpoint
Definition at line 178 of file FixedwingPositionControl.hpp.
Referenced by calculate_target_airspeed(), control_landing(), control_position(), control_takeoff(), Run(), and status_publish().
|
private |
Definition at line 169 of file FixedwingPositionControl.hpp.
Referenced by Run(), and vehicle_status_poll().
|
private |
|
private |
control mode
Definition at line 180 of file FixedwingPositionControl.hpp.
Referenced by control_position(), control_takeoff(), handle_command(), reset_takeoff_state(), Run(), tecs_update_pitch_throttle(), and vehicle_control_mode_poll().
|
private |
control mode subscription
Definition at line 156 of file FixedwingPositionControl.hpp.
Referenced by vehicle_control_mode_poll().
|
private |
last call of control_position
Definition at line 202 of file FixedwingPositionControl.hpp.
Referenced by control_position().
|
private |
Definition at line 240 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll(), and tecs_update_pitch_throttle().
|
private |
Definition at line 221 of file FixedwingPositionControl.hpp.
Referenced by control_landing().
|
private |
estimated height to ground at which flare started
Definition at line 219 of file FixedwingPositionControl.hpp.
Referenced by control_landing().
|
private |
Current forced (i.e. not determined using TECS) flare pitch setpoint.
Definition at line 220 of file FixedwingPositionControl.hpp.
Referenced by control_landing().
|
private |
global vehicle position
Definition at line 181 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), control_position(), control_takeoff(), get_waypoint_heading_distance(), in_takeoff_situation(), Run(), status_publish(), tecs_update_pitch_throttle(), and update_desired_altitude().
|
private |
Definition at line 154 of file FixedwingPositionControl.hpp.
Referenced by FixedwingPositionControl(), init(), and Run().
|
private |
ground speed error to min. speed in m/s
Definition at line 242 of file FixedwingPositionControl.hpp.
|
private |
position to which heading hold flies
Definition at line 200 of file FixedwingPositionControl.hpp.
Referenced by control_position().
|
private |
heading hold enabled
Definition at line 194 of file FixedwingPositionControl.hpp.
Referenced by control_position(), and Run().
|
private |
position where heading hold started
Definition at line 199 of file FixedwingPositionControl.hpp.
Referenced by control_position().
|
private |
hold heading for velocity mode
Definition at line 193 of file FixedwingPositionControl.hpp.
Referenced by control_position().
|
private |
hold altitude for altitude mode
Definition at line 191 of file FixedwingPositionControl.hpp.
Referenced by control_position(), get_waypoint_heading_distance(), Run(), and update_desired_altitude().
|
private |
Definition at line 250 of file FixedwingPositionControl.hpp.
Referenced by get_tecs_pitch(), get_tecs_thrust(), and tecs_update_pitch_throttle().
|
private |
Definition at line 260 of file FixedwingPositionControl.hpp.
Referenced by calculate_target_airspeed(), control_landing(), control_position(), control_takeoff(), init(), and status_publish().
|
private |
Definition at line 210 of file FixedwingPositionControl.hpp.
Referenced by abort_landing(), control_position(), landing_status_publish(), and reset_landing_state().
|
private |
Definition at line 208 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
Definition at line 205 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
Definition at line 206 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), control_position(), and reset_landing_state().
|
private |
Definition at line 209 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
Definition at line 207 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
Definition at line 212 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), init(), and landing_status_publish().
|
private |
true if the last iteration was in manual mode (used to determine when a reset is needed)
Definition at line 234 of file FixedwingPositionControl.hpp.
Referenced by control_position().
|
private |
Definition at line 251 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle().
|
private |
Definition at line 230 of file FixedwingPositionControl.hpp.
Referenced by control_takeoff(), and reset_takeoff_state().
|
private |
Definition at line 229 of file FixedwingPositionControl.hpp.
Referenced by control_position(), control_takeoff(), and reset_takeoff_state().
|
private |
Definition at line 228 of file FixedwingPositionControl.hpp.
Referenced by control_takeoff(), and reset_takeoff_state().
|
private |
vehicle local position
Definition at line 182 of file FixedwingPositionControl.hpp.
Referenced by Run(), and tecs_update_pitch_throttle().
|
private |
Definition at line 157 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
loop performance counter
Definition at line 189 of file FixedwingPositionControl.hpp.
Referenced by print_status(), Run(), and ~FixedwingPositionControl().
|
private |
r/c channel data
Definition at line 175 of file FixedwingPositionControl.hpp.
Referenced by control_position(), get_demanded_airspeed(), Run(), and update_desired_altitude().
|
private |
notification of manual control updates
Definition at line 158 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
Definition at line 152 of file FixedwingPositionControl.hpp.
Referenced by abort_landing(), control_landing(), control_takeoff(), and init().
struct { ... } FixedwingPositionControl::_parameter_handles |
handles for interesting parameters
Referenced by FixedwingPositionControl(), init(), and vehicle_status_poll().
|
private |
notification of parameter updates
Definition at line 159 of file FixedwingPositionControl.hpp.
Referenced by Run().
struct { ... } FixedwingPositionControl::_parameters |
local copies of interesting parameters
Referenced by airspeed_poll(), calculate_target_airspeed(), control_landing(), control_position(), control_takeoff(), do_takeoff_help(), FixedwingPositionControl(), get_demanded_airspeed(), in_takeoff_situation(), init(), Run(), tecs_update_pitch_throttle(), update_desired_altitude(), and vehicle_attitude_poll().
|
private |
Definition at line 246 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle(), and vehicle_attitude_poll().
|
private |
landing status publication
Definition at line 172 of file FixedwingPositionControl.hpp.
Referenced by landing_status_publish().
|
private |
navigation capabilities publication
Definition at line 171 of file FixedwingPositionControl.hpp.
Referenced by status_publish().
|
private |
captures the number of times the estimator has reset the horizontal position
Definition at line 257 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
triplet of mission items
Definition at line 176 of file FixedwingPositionControl.hpp.
Referenced by handle_command(), reset_landing_state(), Run(), and status_publish().
|
private |
Definition at line 160 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
current attitude
Definition at line 244 of file FixedwingPositionControl.hpp.
Referenced by calculate_target_airspeed(), tecs_update_pitch_throttle(), and vehicle_attitude_poll().
|
private |
indicates if the TECS states should be reinitialized (used for VTOL)
Definition at line 249 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle().
|
private |
Definition at line 245 of file FixedwingPositionControl.hpp.
Referenced by vehicle_attitude_poll().
|
private |
Definition at line 232 of file FixedwingPositionControl.hpp.
Referenced by control_position(), control_takeoff(), and reset_takeoff_state().
|
private |
Definition at line 161 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle().
|
private |
last terrain estimate which was valid
Definition at line 216 of file FixedwingPositionControl.hpp.
Referenced by control_landing().
|
private |
ground altitude at which plane was launched
Definition at line 192 of file FixedwingPositionControl.hpp.
Referenced by control_position(), control_takeoff(), do_takeoff_help(), and in_takeoff_situation().
|
private |
estimated height to ground at which flare started
Definition at line 222 of file FixedwingPositionControl.hpp.
Referenced by control_landing().
|
private |
Definition at line 261 of file FixedwingPositionControl.hpp.
Referenced by airspeed_poll(), control_landing(), control_position(), get_tecs_pitch(), get_tecs_thrust(), init(), Run(), tecs_status_publish(), and tecs_update_pitch_throttle().
|
private |
TECS status publication.
Definition at line 173 of file FixedwingPositionControl.hpp.
Referenced by tecs_status_publish().
|
private |
time at which we had last valid terrain alt
Definition at line 217 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
time at which landing started
Definition at line 214 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and reset_landing_state().
|
private |
time at which the plane went in the air
Definition at line 225 of file FixedwingPositionControl.hpp.
Referenced by control_position(), and in_takeoff_situation().
|
private |
Definition at line 187 of file FixedwingPositionControl.hpp.
Referenced by control_takeoff(), Run(), and tecs_update_pitch_throttle().
|
private |
vehicle attitude subscription
Definition at line 162 of file FixedwingPositionControl.hpp.
Referenced by vehicle_attitude_poll().
|
private |
vehicle commands
Definition at line 179 of file FixedwingPositionControl.hpp.
Referenced by handle_command(), and vehicle_command_poll().
|
private |
vehicle command subscription
Definition at line 163 of file FixedwingPositionControl.hpp.
Referenced by vehicle_command_poll().
|
private |
vehicle land detected
Definition at line 183 of file FixedwingPositionControl.hpp.
Referenced by control_position(), reset_takeoff_state(), Run(), and tecs_update_pitch_throttle().
|
private |
vehicle land detected subscription
Definition at line 164 of file FixedwingPositionControl.hpp.
Referenced by Run().
|
private |
Definition at line 166 of file FixedwingPositionControl.hpp.
Referenced by control_position(), and Run().
|
private |
vehicle status
Definition at line 184 of file FixedwingPositionControl.hpp.
Referenced by control_position(), in_takeoff_situation(), Run(), tecs_update_pitch_throttle(), update_desired_altitude(), vehicle_attitude_poll(), and vehicle_status_poll().
|
private |
vehicle status subscription
Definition at line 165 of file FixedwingPositionControl.hpp.
Referenced by vehicle_status_poll().
|
private |
indicated wether the plane was in the air in the previous interation*/
Definition at line 224 of file FixedwingPositionControl.hpp.
Referenced by control_position(), and reset_takeoff_state().
|
private |
wether the last stick input was in althold deadband
Definition at line 197 of file FixedwingPositionControl.hpp.
Referenced by update_desired_altitude().
|
private |
Definition at line 254 of file FixedwingPositionControl.hpp.
Referenced by tecs_update_pitch_throttle().
|
private |
Definition at line 247 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), control_position(), and vehicle_attitude_poll().
|
private |
yaw is locked for heading hold
Definition at line 195 of file FixedwingPositionControl.hpp.
Referenced by control_position().
int32_t FixedwingPositionControl::airspeed_disabled |
Definition at line 281 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::airspeed_disabled |
Definition at line 342 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::airspeed_max |
Definition at line 280 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::airspeed_max |
Definition at line 340 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::airspeed_min |
Definition at line 278 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::airspeed_min |
Definition at line 338 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::airspeed_trans |
Definition at line 309 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::airspeed_trans |
Definition at line 341 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::airspeed_trim |
Definition at line 279 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::airspeed_trim |
Definition at line 339 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::climbout_diff |
Definition at line 271 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::climbout_diff |
Definition at line 314 of file FixedwingPositionControl.hpp.
|
private |
used to check the mode in the last control loop iteration. Use to check if the last iteration was in the same mode.
Referenced by control_position().
param_t FixedwingPositionControl::height_comp_filter_omega |
Definition at line 332 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::heightrate_ff |
Definition at line 327 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::heightrate_p |
Definition at line 326 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::integrator_gain |
Definition at line 330 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::l1_damping |
Definition at line 317 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::l1_period |
Definition at line 316 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::land_airspeed_scale |
Definition at line 305 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_airspeed_scale |
Definition at line 370 of file FixedwingPositionControl.hpp.
int32_t FixedwingPositionControl::land_early_config_change |
Definition at line 304 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_early_config_change |
Definition at line 369 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_flare_alt_relative |
Definition at line 363 of file FixedwingPositionControl.hpp.
Referenced by init().
float FixedwingPositionControl::land_flare_pitch_max_deg |
Definition at line 302 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_flare_pitch_max_deg |
Definition at line 367 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::land_flare_pitch_min_deg |
Definition at line 301 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_flare_pitch_min_deg |
Definition at line 366 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_H1_virt |
Definition at line 362 of file FixedwingPositionControl.hpp.
Referenced by init().
float FixedwingPositionControl::land_heading_hold_horizontal_distance |
Definition at line 300 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_heading_hold_horizontal_distance |
Definition at line 365 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_slope_angle |
Definition at line 361 of file FixedwingPositionControl.hpp.
Referenced by init().
float FixedwingPositionControl::land_throtTC_scale |
Definition at line 306 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_throtTC_scale |
Definition at line 371 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_thrust_lim_alt_relative |
Definition at line 364 of file FixedwingPositionControl.hpp.
Referenced by init().
int32_t FixedwingPositionControl::land_use_terrain_estimate |
Definition at line 303 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::land_use_terrain_estimate |
Definition at line 368 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::loiter_radius |
Definition at line 298 of file FixedwingPositionControl.hpp.
Referenced by control_position().
param_t FixedwingPositionControl::loiter_radius |
Definition at line 372 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::man_pitch_max_deg |
Definition at line 355 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::man_pitch_max_rad |
Definition at line 293 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::man_roll_max_deg |
Definition at line 354 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::man_roll_max_rad |
Definition at line 292 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::max_climb_rate |
Definition at line 273 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::max_climb_rate |
Definition at line 325 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::max_sink_rate |
Definition at line 274 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::max_sink_rate |
Definition at line 324 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::min_sink_rate |
Definition at line 323 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::pitch_damping |
Definition at line 336 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::pitch_limit_max |
Definition at line 284 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::pitch_limit_max |
Definition at line 345 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::pitch_limit_min |
Definition at line 283 of file FixedwingPositionControl.hpp.
Referenced by control_position().
param_t FixedwingPositionControl::pitch_limit_min |
Definition at line 344 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::pitchsp_offset_deg |
Definition at line 357 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::pitchsp_offset_rad |
Definition at line 295 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::roll_limit |
Definition at line 318 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::roll_slew_deg_sec |
Definition at line 319 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::roll_throttle_compensation |
Definition at line 334 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::rollsp_offset_deg |
Definition at line 356 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::rollsp_offset_rad |
Definition at line 294 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::speed_comp_filter_omega |
Definition at line 333 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::speed_weight |
Definition at line 275 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::speed_weight |
Definition at line 335 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::speedrate_p |
Definition at line 328 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_alt_scale |
Definition at line 290 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_alt_scale |
Definition at line 352 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_cruise |
Definition at line 289 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_cruise |
Definition at line 350 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_damp |
Definition at line 329 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_idle |
Definition at line 288 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_idle |
Definition at line 349 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_land_max |
Definition at line 297 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_land_max |
Definition at line 359 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_max |
Definition at line 287 of file FixedwingPositionControl.hpp.
Referenced by control_landing(), and control_position().
param_t FixedwingPositionControl::throttle_max |
Definition at line 348 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::throttle_min |
Definition at line 286 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_min |
Definition at line 347 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::throttle_slew_max |
Definition at line 351 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::time_const |
Definition at line 321 of file FixedwingPositionControl.hpp.
float FixedwingPositionControl::time_const_throt |
Definition at line 276 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::time_const_throt |
Definition at line 322 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::vertical_accel_limit |
Definition at line 331 of file FixedwingPositionControl.hpp.
int32_t FixedwingPositionControl::vtol_type |
Definition at line 310 of file FixedwingPositionControl.hpp.
param_t FixedwingPositionControl::vtol_type |
Definition at line 374 of file FixedwingPositionControl.hpp.