Plane: review fixes

thanks Pete!
This commit is contained in:
Andrew Tridgell 2022-03-09 13:16:32 +11:00
parent c658f170cb
commit cc9b9813cb
5 changed files with 28 additions and 11 deletions

View File

@ -185,7 +185,7 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const
targets.y * 0.01, targets.y * 0.01,
targets.z * 0.01, targets.z * 0.01,
degrees(error.angle()), degrees(error.angle()),
error.length(), MIN(error.length(), UINT16_MAX),
(plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0, (plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0,
plane.airspeed_error * 100, // incorrect units; see PR#7933 plane.airspeed_error * 100, // incorrect units; see PR#7933
quadplane.wp_nav->crosstrack_error()); quadplane.wp_nav->crosstrack_error());

View File

@ -23,7 +23,7 @@ void Plane::Log_Write_Attitude(void)
} else { } else {
ahrs.Write_Attitude(targets); ahrs.Write_Attitude(targets);
} }
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight() || quadplane.in_vtol_airbrake()) { if (AP_HAL::millis() - quadplane.last_att_control_ms < 100) {
// log quadplane PIDs separately from fixed wing PIDs // log quadplane PIDs separately from fixed wing PIDs
logger.Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); logger.Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());

View File

@ -80,6 +80,10 @@ bool Mode::enter()
// initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands // initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands
plane.new_airspeed_cm = -1; plane.new_airspeed_cm = -1;
#if HAL_QUADPLANE_ENABLED
quadplane.mode_enter();
#endif
bool enter_result = _enter(); bool enter_result = _enter();
if (enter_result) { if (enter_result) {

View File

@ -2400,7 +2400,8 @@ void QuadPlane::vtol_position_controller(void)
const Vector2f diff_wp = plane.current_loc.get_distance_NE(loc); const Vector2f diff_wp = plane.current_loc.get_distance_NE(loc);
const float distance = diff_wp.length(); const float distance = diff_wp.length();
const float groundspeed = plane.ahrs.groundspeed(); const Vector2f rel_groundspeed_vector = landing_closing_velocity();
const float rel_groundspeed_sq = rel_groundspeed_vector.length_squared();
// calculate speed we should be at to reach the position2 // calculate speed we should be at to reach the position2
// target speed at the position2 distance threshold, assuming // target speed at the position2 distance threshold, assuming
@ -2411,14 +2412,13 @@ void QuadPlane::vtol_position_controller(void)
// maximum configured VTOL speed // maximum configured VTOL speed
const float wp_speed = wp_nav->get_default_speed_xy() * 0.01; const float wp_speed = wp_nav->get_default_speed_xy() * 0.01;
const float current_speed_sq = plane.ahrs.groundspeed_vector().length_squared();
const float scaled_wp_speed = get_scaled_wp_speed(degrees(diff_wp.angle())); const float scaled_wp_speed = get_scaled_wp_speed(degrees(diff_wp.angle()));
// limit target speed to initial pos1 speed, but at least twice the Q_WP_SPEED // limit target speed to initial pos1 speed, but at least twice the Q_WP_SPEED
target_speed = MIN(MAX(poscontrol.pos1_start_speed, 2*wp_speed), target_speed); target_speed = MIN(MAX(poscontrol.pos1_start_speed, 2*wp_speed), target_speed);
if (poscontrol.reached_wp_speed || if (poscontrol.reached_wp_speed ||
current_speed_sq < sq(wp_speed) || rel_groundspeed_sq < sq(wp_speed) ||
wp_speed > 1.35*scaled_wp_speed) { wp_speed > 1.35*scaled_wp_speed) {
// once we get below the Q_WP_SPEED then we don't want to // once we get below the Q_WP_SPEED then we don't want to
// speed up again. At that point we should fly within the // speed up again. At that point we should fly within the
@ -2435,7 +2435,7 @@ void QuadPlane::vtol_position_controller(void)
Vector2f target_speed_xy_cms; Vector2f target_speed_xy_cms;
Vector2f target_accel_cms; Vector2f target_accel_cms;
const float target_accel = accel_needed(distance, sq(groundspeed)); const float target_accel = accel_needed(distance, rel_groundspeed_sq);
if (distance > 0.1) { if (distance > 0.1) {
Vector2f diff_wp_norm = diff_wp.normalized(); Vector2f diff_wp_norm = diff_wp.normalized();
target_speed_xy_cms = diff_wp_norm * target_speed * 100; target_speed_xy_cms = diff_wp_norm * target_speed * 100;
@ -3722,14 +3722,16 @@ bool QuadPlane::use_fw_attitude_controllers(void) const
} }
/* /*
calculate our closing velocity vector on the landing point. In the calculate our closing velocity vector on the landing point, taking
future this will take account of the landing point having a into account target velocity
velocity
*/ */
Vector2f QuadPlane::landing_closing_velocity() Vector2f QuadPlane::landing_closing_velocity()
{ {
Vector2f vel = ahrs.groundspeed_vector(); Vector2f landing_velocity;
return vel; if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) {
landing_velocity = poscontrol.velocity_match;
}
return ahrs.groundspeed_vector() - landing_velocity;
} }
/* /*
@ -3927,4 +3929,12 @@ bool QuadPlane::in_vtol_takeoff(void) const
return false; return false;
} }
// called when we change mode (for any mode, not just Q modes)
void QuadPlane::mode_enter(void)
{
poscontrol.xy_correction.zero();
poscontrol.velocity_match.zero();
poscontrol.last_velocity_match_ms = 0;
}
#endif // HAL_QUADPLANE_ENABLED #endif // HAL_QUADPLANE_ENABLED

View File

@ -164,6 +164,9 @@ public:
}; };
void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;}; void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;};
// called when we change mode (for any mode, not just Q modes)
void mode_enter(void);
private: private:
AP_AHRS &ahrs; AP_AHRS &ahrs;
AP_Vehicle::MultiCopter aparm; AP_Vehicle::MultiCopter aparm;