Skip to content

Commit

Permalink
Plane: QAssist speed warning added
Browse files Browse the repository at this point in the history
Also updated the severity of other QAssist messages
  • Loading branch information
LachlanConn authored and peterbarker committed Dec 13, 2023
1 parent 71a64d5 commit d5cc1d4
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1496,7 +1496,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed)
// we've been below assistant alt for Q_ASSIST_DELAY seconds
if (!in_alt_assist) {
in_alt_assist = true;
gcs().send_text(MAV_SEVERITY_INFO, "Alt assist %.1fm", height_above_ground);
gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground);
}
return true;
}
Expand Down Expand Up @@ -1541,7 +1541,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed)
bool ret = (now - angle_error_start_ms) >= assist_delay*1000;
if (ret && !in_angle_assist) {
in_angle_assist = true;
gcs().send_text(MAV_SEVERITY_INFO, "Angle assist r=%d p=%d",
gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d",
(int)(ahrs.roll_sensor/100),
(int)(ahrs.pitch_sensor/100));
}
Expand Down

0 comments on commit d5cc1d4

Please sign in to comment.