|
|
@ -762,7 +762,7 @@ bool QuadPlane::setup(void) |
|
|
|
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); |
|
|
|
hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); |
|
|
|
|
|
|
|
|
|
|
|
// default QAssist state as set with Q_OPTIONS
|
|
|
|
// default QAssist state as set with Q_OPTIONS
|
|
|
|
if ((options & OPTION_Q_ASSIST_FORCE_ENABLE) != 0) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::Q_ASSIST_FORCE_ENABLE)) { |
|
|
|
q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; |
|
|
|
q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -1190,7 +1190,7 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground) |
|
|
|
height_above_ground, |
|
|
|
height_above_ground, |
|
|
|
land_final_alt, land_final_alt+6); |
|
|
|
land_final_alt, land_final_alt+6); |
|
|
|
|
|
|
|
|
|
|
|
if ((options & OPTION_THR_LANDING_CONTROL) != 0) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::THR_LANDING_CONTROL)) { |
|
|
|
// allow throttle control for landing speed
|
|
|
|
// allow throttle control for landing speed
|
|
|
|
const float thr_in = get_pilot_land_throttle(); |
|
|
|
const float thr_in = get_pilot_land_throttle(); |
|
|
|
if (thr_in > THR_CTRL_LAND_THRESH) { |
|
|
|
if (thr_in > THR_CTRL_LAND_THRESH) { |
|
|
@ -1409,7 +1409,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) |
|
|
|
// assistance due to Q_ASSIST_SPEED
|
|
|
|
// assistance due to Q_ASSIST_SPEED
|
|
|
|
// if option bit is enabled only allow assist with real airspeed sensor
|
|
|
|
// if option bit is enabled only allow assist with real airspeed sensor
|
|
|
|
if ((have_airspeed && aspeed < assist_speed) &&
|
|
|
|
if ((have_airspeed && aspeed < assist_speed) &&
|
|
|
|
(((options & OPTION_DISABLE_SYNTHETIC_AIRSPEED_ASSIST) == 0) || ahrs.airspeed_sensor_enabled())) { |
|
|
|
(!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.airspeed_sensor_enabled())) { |
|
|
|
in_angle_assist = false; |
|
|
|
in_angle_assist = false; |
|
|
|
angle_error_start_ms = 0; |
|
|
|
angle_error_start_ms = 0; |
|
|
|
return true; |
|
|
|
return true; |
|
|
@ -1568,7 +1568,7 @@ void SLT_Transition::update() |
|
|
|
// if option is set and ground speed> 1/2 arspd_fbw_min for non-tiltrotors, then complete transition, otherwise QLAND.
|
|
|
|
// if option is set and ground speed> 1/2 arspd_fbw_min for non-tiltrotors, then complete transition, otherwise QLAND.
|
|
|
|
// tiltrotors will immediately transition
|
|
|
|
// tiltrotors will immediately transition
|
|
|
|
const bool tiltrotor_with_ground_speed = quadplane.tiltrotor.enabled() && (plane.ahrs.groundspeed() > plane.aparm.airspeed_min * 0.5); |
|
|
|
const bool tiltrotor_with_ground_speed = quadplane.tiltrotor.enabled() && (plane.ahrs.groundspeed() > plane.aparm.airspeed_min * 0.5); |
|
|
|
if ((quadplane.options & QuadPlane::OPTION_TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) { |
|
|
|
if (quadplane.option_is_set(QuadPlane::OPTION::TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) { |
|
|
|
transition_state = TRANSITION_TIMER; |
|
|
|
transition_state = TRANSITION_TIMER; |
|
|
|
in_forced_transition = true; |
|
|
|
in_forced_transition = true; |
|
|
|
} else { |
|
|
|
} else { |
|
|
@ -1604,7 +1604,7 @@ void SLT_Transition::update() |
|
|
|
// otherwise the plane can end up in high-alpha flight with
|
|
|
|
// otherwise the plane can end up in high-alpha flight with
|
|
|
|
// low VTOL thrust and may not complete a transition
|
|
|
|
// low VTOL thrust and may not complete a transition
|
|
|
|
float climb_rate_cms = quadplane.assist_climb_rate_cms(); |
|
|
|
float climb_rate_cms = quadplane.assist_climb_rate_cms(); |
|
|
|
if ((quadplane.options & QuadPlane::OPTION_LEVEL_TRANSITION) && !quadplane.tiltrotor.enabled()) { |
|
|
|
if (quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION) && !quadplane.tiltrotor.enabled()) { |
|
|
|
climb_rate_cms = MIN(climb_rate_cms, 0.0f); |
|
|
|
climb_rate_cms = MIN(climb_rate_cms, 0.0f); |
|
|
|
} |
|
|
|
} |
|
|
|
quadplane.hold_hover(climb_rate_cms); |
|
|
|
quadplane.hold_hover(climb_rate_cms); |
|
|
@ -1957,7 +1957,7 @@ void QuadPlane::motors_output(bool run_rate_controller) |
|
|
|
1) for safety (OPTION_DELAY_ARMING) |
|
|
|
1) for safety (OPTION_DELAY_ARMING) |
|
|
|
2) to allow motors to return to vertical (OPTION_DISARMED_TILT) |
|
|
|
2) to allow motors to return to vertical (OPTION_DISARMED_TILT) |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
if ((options & OPTION_DISARMED_TILT) || (options & OPTION_DELAY_ARMING)) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::DISARMED_TILT) || option_is_set(QuadPlane::OPTION::DELAY_ARMING)) { |
|
|
|
if (plane.arming.get_delay_arming()) { |
|
|
|
if (plane.arming.get_delay_arming()) { |
|
|
|
// delay motor start after arming
|
|
|
|
// delay motor start after arming
|
|
|
|
set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); |
|
|
|
set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); |
|
|
@ -2143,7 +2143,7 @@ bool QuadPlane::in_vtol_posvel_mode(void) const |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
void QuadPlane::update_land_positioning(void) |
|
|
|
void QuadPlane::update_land_positioning(void) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if ((options & OPTION_REPOSITION_LANDING) == 0) { |
|
|
|
if (!option_is_set(QuadPlane::OPTION::REPOSITION_LANDING)) { |
|
|
|
// not enabled
|
|
|
|
// not enabled
|
|
|
|
poscontrol.pilot_correction_active = false; |
|
|
|
poscontrol.pilot_correction_active = false; |
|
|
|
poscontrol.target_vel_cms.zero(); |
|
|
|
poscontrol.target_vel_cms.zero(); |
|
|
@ -2195,7 +2195,7 @@ void QuadPlane::run_xy_controller(float accel_limit) |
|
|
|
void QuadPlane::poscontrol_init_approach(void) |
|
|
|
void QuadPlane::poscontrol_init_approach(void) |
|
|
|
{ |
|
|
|
{ |
|
|
|
const float dist = plane.current_loc.get_distance(plane.next_WP_loc); |
|
|
|
const float dist = plane.current_loc.get_distance(plane.next_WP_loc); |
|
|
|
if ((options & OPTION_DISABLE_APPROACH) != 0) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) { |
|
|
|
// go straight to QPOS_POSITION1
|
|
|
|
// go straight to QPOS_POSITION1
|
|
|
|
poscontrol.set_state(QPOS_POSITION1); |
|
|
|
poscontrol.set_state(QPOS_POSITION1); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); |
|
|
@ -2801,7 +2801,7 @@ void QuadPlane::vtol_position_controller(void) |
|
|
|
case QPOS_LAND_FINAL: { |
|
|
|
case QPOS_LAND_FINAL: { |
|
|
|
float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); |
|
|
|
float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); |
|
|
|
if (poscontrol.get_state() == QPOS_LAND_FINAL) { |
|
|
|
if (poscontrol.get_state() == QPOS_LAND_FINAL) { |
|
|
|
if ((options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { |
|
|
|
if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { |
|
|
|
ahrs.set_touchdown_expected(true); |
|
|
|
ahrs.set_touchdown_expected(true); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -3070,7 +3070,7 @@ bool QuadPlane::do_vtol_takeoff(const AP_Mission::Mission_Command& cmd) |
|
|
|
loc.lat = 0; |
|
|
|
loc.lat = 0; |
|
|
|
loc.lng = 0; |
|
|
|
loc.lng = 0; |
|
|
|
plane.set_next_WP(loc); |
|
|
|
plane.set_next_WP(loc); |
|
|
|
if (options & OPTION_RESPECT_TAKEOFF_FRAME) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::RESPECT_TAKEOFF_FRAME)) { |
|
|
|
if (plane.current_loc.alt >= plane.next_WP_loc.alt) { |
|
|
|
if (plane.current_loc.alt >= plane.next_WP_loc.alt) { |
|
|
|
// we are above the takeoff already, no need to do anything
|
|
|
|
// we are above the takeoff already, no need to do anything
|
|
|
|
return false; |
|
|
|
return false; |
|
|
@ -3164,7 +3164,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (now - takeoff_start_time_ms < 3000 && |
|
|
|
if (now - takeoff_start_time_ms < 3000 && |
|
|
|
(options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { |
|
|
|
!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { |
|
|
|
ahrs.set_takeoff_expected(true); |
|
|
|
ahrs.set_takeoff_expected(true); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -3657,7 +3657,7 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude) |
|
|
|
guided_start(); |
|
|
|
guided_start(); |
|
|
|
guided_takeoff = true; |
|
|
|
guided_takeoff = true; |
|
|
|
guided_wait_takeoff = false; |
|
|
|
guided_wait_takeoff = false; |
|
|
|
if ((options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { |
|
|
|
if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { |
|
|
|
ahrs.set_takeoff_expected(true); |
|
|
|
ahrs.set_takeoff_expected(true); |
|
|
|
} |
|
|
|
} |
|
|
|
return true; |
|
|
|
return true; |
|
|
@ -3691,7 +3691,7 @@ bool QuadPlane::is_vtol_takeoff(uint16_t id) const |
|
|
|
if (id == MAV_CMD_NAV_VTOL_TAKEOFF) { |
|
|
|
if (id == MAV_CMD_NAV_VTOL_TAKEOFF) { |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
if (id == MAV_CMD_NAV_TAKEOFF && available() && (options & OPTION_ALLOW_FW_TAKEOFF) == 0) { |
|
|
|
if (id == MAV_CMD_NAV_TAKEOFF && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_TAKEOFF)) { |
|
|
|
// treat fixed wing takeoff as VTOL takeoff
|
|
|
|
// treat fixed wing takeoff as VTOL takeoff
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
@ -3704,13 +3704,13 @@ bool QuadPlane::is_vtol_takeoff(uint16_t id) const |
|
|
|
bool QuadPlane::is_vtol_land(uint16_t id) const |
|
|
|
bool QuadPlane::is_vtol_land(uint16_t id) const |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (id == MAV_CMD_NAV_VTOL_LAND) { |
|
|
|
if (id == MAV_CMD_NAV_VTOL_LAND) { |
|
|
|
if (options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) { |
|
|
|
if (option_is_set(QuadPlane::OPTION::MISSION_LAND_FW_APPROACH)) { |
|
|
|
return plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING; |
|
|
|
return plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING; |
|
|
|
} else { |
|
|
|
} else { |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
if (id == MAV_CMD_NAV_LAND && available() && (options & OPTION_ALLOW_FW_LAND) == 0) { |
|
|
|
if (id == MAV_CMD_NAV_LAND && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) { |
|
|
|
// treat fixed wing land as VTOL land
|
|
|
|
// treat fixed wing land as VTOL land
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
@ -4075,7 +4075,7 @@ QuadPlane *QuadPlane::_singleton = nullptr; |
|
|
|
bool SLT_Transition::set_FW_roll_limit(int32_t& roll_limit_cd) |
|
|
|
bool SLT_Transition::set_FW_roll_limit(int32_t& roll_limit_cd) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER) && |
|
|
|
if (quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER) && |
|
|
|
(quadplane.options & QuadPlane::OPTION_LEVEL_TRANSITION)) { |
|
|
|
quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION)) { |
|
|
|
// the user wants transitions to be kept level to within LEVEL_ROLL_LIMIT
|
|
|
|
// the user wants transitions to be kept level to within LEVEL_ROLL_LIMIT
|
|
|
|
roll_limit_cd = MIN(roll_limit_cd, plane.g.level_roll_limit*100); |
|
|
|
roll_limit_cd = MIN(roll_limit_cd, plane.g.level_roll_limit*100); |
|
|
|
return true; |
|
|
|
return true; |
|
|
@ -4290,7 +4290,7 @@ bool QuadPlane::allow_servo_auto_trim() |
|
|
|
// In forward flight and VTOL motors not active
|
|
|
|
// In forward flight and VTOL motors not active
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
if (tailsitter.enabled() && ((options & QuadPlane::OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY) != 0)) { |
|
|
|
if (tailsitter.enabled() && option_is_set(QuadPlane::OPTION::TAILSIT_Q_ASSIST_MOTORS_ONLY)) { |
|
|
|
// Tailsitter in forward flight, motors providing active stabalisation with motors only option
|
|
|
|
// Tailsitter in forward flight, motors providing active stabalisation with motors only option
|
|
|
|
// Control surfaces are running as normal with I term active, motor I term is zeroed
|
|
|
|
// Control surfaces are running as normal with I term active, motor I term is zeroed
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|