APM:Libraries
|
#include <AP_Vehicle.h>
Classes | |
struct | Rangefinder_State |
Public Types | |
enum | FlightStage { FLIGHT_TAKEOFF = 1, FLIGHT_VTOL = 2, FLIGHT_NORMAL = 3, FLIGHT_LAND = 4, FLIGHT_ABORT_LAND = 7 } |
Public Attributes | |
AP_Int8 | throttle_min |
AP_Int8 | throttle_max |
AP_Int8 | throttle_slewrate |
AP_Int8 | throttle_cruise |
AP_Int8 | takeoff_throttle_max |
AP_Int16 | airspeed_min |
AP_Int16 | airspeed_max |
AP_Int32 | airspeed_cruise_cm |
AP_Int32 | min_gndspeed_cm |
AP_Int8 | crash_detection_enable |
AP_Int16 | roll_limit_cd |
AP_Int16 | pitch_limit_max_cd |
AP_Int16 | pitch_limit_min_cd |
AP_Int8 | autotune_level |
AP_Int8 | stall_prevention |
AP_Int16 | loiter_radius |
Definition at line 30 of file AP_Vehicle.h.
Enumerator | |
---|---|
FLIGHT_TAKEOFF | |
FLIGHT_VTOL | |
FLIGHT_NORMAL | |
FLIGHT_LAND | |
FLIGHT_ABORT_LAND |
Definition at line 64 of file AP_Vehicle.h.
AP_Int32 AP_Vehicle::FixedWing::airspeed_cruise_cm |
Definition at line 38 of file AP_Vehicle.h.
Referenced by AP_Landing::get_target_airspeed_cm(), AP_Landing_Deepstall::get_target_airspeed_cm(), AP_Landing::type_slope_get_target_airspeed_cm(), AP_Landing::type_slope_verify_land(), and Variometer::update().
AP_Int16 AP_Vehicle::FixedWing::airspeed_max |
Definition at line 37 of file AP_Vehicle.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_TECS::_update_speed(), AP_PitchController::get_rate_out(), and AP_YawController::get_servo_out().
AP_Int16 AP_Vehicle::FixedWing::airspeed_min |
Definition at line 36 of file AP_Vehicle.h.
Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_TECS::_update_speed(), AP_PitchController::get_rate_out(), and AP_YawController::get_servo_out().
AP_Int8 AP_Vehicle::FixedWing::autotune_level |
Definition at line 44 of file AP_Vehicle.h.
Referenced by AP_AutoTune::check_state_exit(), and AP_AutoTune::start().
AP_Int8 AP_Vehicle::FixedWing::crash_detection_enable |
Definition at line 40 of file AP_Vehicle.h.
Referenced by AP_Landing::type_slope_verify_land().
AP_Int16 AP_Vehicle::FixedWing::loiter_radius |
Definition at line 46 of file AP_Vehicle.h.
Referenced by AP_Landing_Deepstall::build_approach_path(), and AP_Landing_Deepstall::verify_land().
AP_Int32 AP_Vehicle::FixedWing::min_gndspeed_cm |
Definition at line 39 of file AP_Vehicle.h.
Referenced by AP_Landing::type_slope_verify_land().
AP_Int16 AP_Vehicle::FixedWing::pitch_limit_max_cd |
Definition at line 42 of file AP_Vehicle.h.
Referenced by AP_TECS::update_pitch_throttle().
AP_Int16 AP_Vehicle::FixedWing::pitch_limit_min_cd |
Definition at line 43 of file AP_Vehicle.h.
Referenced by AP_TECS::update_pitch_throttle().
AP_Int16 AP_Vehicle::FixedWing::roll_limit_cd |
Definition at line 41 of file AP_Vehicle.h.
Referenced by AP_PitchController::_get_rate_out().
AP_Int8 AP_Vehicle::FixedWing::stall_prevention |
Definition at line 45 of file AP_Vehicle.h.
Referenced by AP_TECS::_update_speed().
AP_Int8 AP_Vehicle::FixedWing::takeoff_throttle_max |
Definition at line 35 of file AP_Vehicle.h.
Referenced by AP_TECS::update_pitch_throttle().
AP_Int8 AP_Vehicle::FixedWing::throttle_cruise |
Definition at line 34 of file AP_Vehicle.h.
Referenced by AP_TECS::_initialise_states(), AP_TECS::_update_throttle_with_airspeed(), AP_TECS::_update_throttle_without_airspeed(), and AP_Landing::type_slope_verify_land().
AP_Int8 AP_Vehicle::FixedWing::throttle_max |
Definition at line 32 of file AP_Vehicle.h.
Referenced by AP_TECS::update_pitch_throttle().
AP_Int8 AP_Vehicle::FixedWing::throttle_min |
Definition at line 31 of file AP_Vehicle.h.
Referenced by AP_TECS::update_pitch_throttle().
AP_Int8 AP_Vehicle::FixedWing::throttle_slewrate |
Definition at line 33 of file AP_Vehicle.h.
Referenced by AP_TECS::_update_throttle_with_airspeed().