176 throttle_suppressed =
false;
185 const float height,
const float sink_rate,
const float wp_proportion,
const uint32_t last_flying_ms,
186 const bool is_armed,
const bool is_flying,
const bool rangefinder_state_in_range)
253 degrees(atan2f(-groundspeed.
y, -groundspeed.
x) +
M_PI))) >= 10.0f)) {
265 float height_above_target;
268 height_above_target = -height_above_target;
295 if (elevator !=
nullptr) {
321 if (elevator ==
nullptr) {
323 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Deepstall: Unable to find the elevator channels");
329 float slew_progress = 1.0f;
336 slew_progress, 0.0
f, 1.0
f));
366 float current_altitude_d;
411 mavlink_msg_deepstall_send(
493 float loiter_radius_m_abs = fabsf(loiter_radius);
496 approach_extension_m =
MAX(approach_extension_m, loiter_radius_m_abs * 0.5
f);
510 gcs().
send_text(MAV_SEVERITY_INFO,
"Loiter en: %3.8f %3.8f",
512 gcs().
send_text(MAV_SEVERITY_INFO,
"Loiter ex: %3.8f %3.8f",
514 gcs().
send_text(MAV_SEVERITY_INFO,
"Extended: %3.8f %3.8f",
516 gcs().
send_text(MAV_SEVERITY_INFO,
"Extended by: %f (%f)", (
double)approach_extension_m,
517 (
double)expected_travel_distance);
519 #endif // DEBUG_PRINTS 525 bool reverse =
false;
533 float wind_length =
MAX(wind_vec.
length(), 0.05f);
534 Vector2f course_vec(cosf(course), sinf(course));
536 float offset = course - atan2f(-wind.
y, -wind.
x);
539 float stall_distance =
slope_a * wind_length * cosf(offset) +
slope_b;
541 float theta = acosf(
constrain_float((wind_vec * course_vec) / wind_length, -1.0
f, 1.0
f));
542 if ((course_vec % wind_vec) > 0) {
547 float cross_component = sinf(theta) * wind_length;
548 float estimated_crab_angle = asinf(
constrain_float(cross_component / forward_speed_ms, -1.0
f, 1.0
f));
550 estimated_crab_angle *= -1;
553 float estimated_forward = cosf(estimated_crab_angle) * forward_speed_ms + cosf(theta) * wind_length;
565 gcs().
send_text(MAV_SEVERITY_INFO,
"Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)",
573 const float height_error)
const 595 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Deepstall: Invalid data from AHRS. Holding level");
599 float desired_change = 0.0f;
612 float nu1 = asinf(sine_nu1);
627 gcs().
send_text(MAV_SEVERITY_INFO,
"x: %f e: %f r: %f d: %f",
632 #endif // DEBUG_PRINTS
#define DEEPSTALL_LOITER_ALT_TOLERANCE
static const struct AP_Param::GroupInfo var_info[]
int32_t last_target_bearing
int32_t get_target_airspeed_cm(void) const
void location_update(struct Location &loc, float bearing, float distance)
bool is_on_approach(void) const
float update_steering(void)
void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
bool get_target_altitude_location(Location &location)
virtual int32_t target_bearing_cd(void) const =0
virtual const Vector3f & get_gyro(void) const =0
virtual bool reached_loiter_target(void)=0
AP_Float pre_flare_airspeed
AP_Float handoff_lower_limit_airspeed
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
virtual void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min=0.0f)=0
virtual Vector3f wind_estimate(void) const =0
uint16_t initial_elevator_pwm
#define AP_GROUPINFO(name, idx, clazz, element, def)
float get_distance(const struct Location &loc1, const struct Location &loc2)
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
void WriteBlock(const void *pBuffer, uint16_t size)
virtual bool airspeed_estimate(float *airspeed_ret) const
bool is_positive(const T fVal1)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
bool override_servos(void)
void build_approach_path(bool use_current_heading)
float predicted_travel_distance
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
virtual Vector2f groundspeed_vector(void)
int32_t lat
param 3 - Latitude * 10**7
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
virtual void update_loiter(const struct Location ¢er_WP, float radius, int8_t loiter_direction)=0
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
AP_Float handoff_airspeed
const DataFlash_Class::PID_Info & get_pid_info(void) const
float angle(const Vector2< T > &v2) const
float predict_travel_distance(const Vector3f wind, const float height, const bool print)
AP_Navigation * nav_controller
float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high)
float wrap_180(const T angle, float unit_mod)
virtual float loiter_radius(const float radius) const =0
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
float wrap_PI(const T radian)
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
#define CHECK_PAYLOAD_SIZE2(id)
bool is_zero(const T fVal1)
Object managing one PID control.
bool request_go_around(void)
Class managing Plane Deepstall landing methods.
bool send_deepstall_message(mavlink_channel_t chan) const
void reset()
Reset the whole PID state.
static DataFlash_Class * instance(void)
struct AP_Landing::@124 flags
bool verify_breakout(const Location ¤t_loc, const Location &target_loc, const float height_error) const
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
bool is_throttle_suppressed(void) const
float constrain_float(const float amt, const float low, const float high)
int32_t lng
param 4 - Longitude * 10**7
uint16_t get_output_pwm(void) const
static constexpr float radians(float deg)
float get_pid(float error, float scaler=1.0)
virtual bool healthy(void) const =0
AP_HAL::AnalogSource * chan
float approach_alt_offset
#define error(fmt, args ...)
Location extended_approach
AP_Vehicle::FixedWing & aparm
uint32_t stall_entry_time
bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range)
AP_Float approach_extension
bool is_flying_forward(void) const
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
virtual void update_heading_hold(int32_t navigation_heading_cd)=0
bool location_passed_point(const struct Location &location, const struct Location &point1, const struct Location &point2)
#define LOG_PACKET_HEADER_INIT(id)
void set_output_pwm(uint16_t pwm)
virtual void get_relative_position_D_home(float &posD) const =0
Location breakout_location
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
AP_Int32 airspeed_cruise_cm
const DataFlash_Class::PID_Info & get_pid_info(void) const