41 #ifndef RUNWAYTAKEOFF_H 42 #define RUNWAYTAKEOFF_H 49 #include <px4_platform_common/module_params.h> 51 #include <mathlib/mathlib.h> 71 void init(
float yaw,
double current_lat,
double current_lon);
83 float getPitch(
float tecsPitch);
84 float getRoll(
float navigatorRoll);
85 float getYaw(
float navigatorYaw);
86 float getThrottle(
float tecsThrottle);
87 bool resetIntegrators();
88 float getMinPitch(
float sp_min,
float climbout_min,
float min);
89 float getMaxPitch(
float max);
104 (ParamBool<px4::params::RWTO_TKOFF>) _param_rwto_tkoff,
105 (ParamInt<px4::params::RWTO_HDG>) _param_rwto_hdg,
106 (ParamFloat<px4::params::RWTO_NAV_ALT>) _param_rwto_nav_alt,
107 (ParamFloat<px4::params::RWTO_MAX_THR>) _param_rwto_max_thr,
108 (ParamFloat<px4::params::RWTO_PSP>) _param_rwto_psp,
109 (ParamFloat<px4::params::RWTO_MAX_PITCH>) _param_rwto_max_pitch,
110 (ParamFloat<px4::params::RWTO_MAX_ROLL>) _param_rwto_max_roll,
111 (ParamFloat<px4::params::RWTO_AIRSPD_SCL>) _param_rwto_airspd_scl,
112 (ParamFloat<px4::params::RWTO_RAMP_TIME>) _param_rwto_ramp_time,
113 (ParamFloat<px4::params::FW_AIRSPD_MIN>) _param_fw_airspd_min,
114 (ParamFloat<px4::params::FW_CLMBOUT_DIFF>) _param_fw_clmbout_diff
121 #endif // RUNWAYTAKEOFF_H static orb_advert_t * mavlink_log_pub
taking off, get ground clearance, roll 0
int reset(enum LPS22HB_BUS busid)
Reset the driver.
RunwayTakeoffState _state
state variables
High-resolution timer with callouts and timekeeping.
float getMinAirspeedScaling()
void init()
Activates/configures the hardware registers.
fly towards takeoff waypoint
bool runwayTakeoffEnabled()
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
constexpr _Tp min(_Tp a, _Tp b)
constexpr _Tp max(_Tp a, _Tp b)
clamped to runway, controlling yaw directly (wheel or rudder)
matrix::Vector2f _start_wp
RunwayTakeoffState getState()
climbout to safe height before navigation, roll limited
hrt_abstime _initialized_time