mirror of https://github.com/ArduPilot/ardupilot
Plane: replace `is_guided_mode` with `is_guided_or_adsb_mode`
This commit is contained in:
parent
613b835d67
commit
8dc58b8e08
|
@ -484,7 +484,7 @@ int16_t Plane::calc_nav_yaw_coordinated()
|
|||
bool using_rate_controller = false;
|
||||
|
||||
// Received an external msg that guides yaw in the last 3 seconds?
|
||||
if (control_mode->is_guided_mode() &&
|
||||
if (control_mode->is_guided_or_adsb_mode() &&
|
||||
plane.guided_state.last_forced_rpy_ms.z > 0 &&
|
||||
millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {
|
||||
commanded_rudder = plane.guided_state.forced_rpy_cd.z;
|
||||
|
|
|
@ -1129,7 +1129,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_comma
|
|||
// controlled modes (e.g., MANUAL, TRAINING)
|
||||
// this command should be ignored since it comes in from GCS
|
||||
// or a companion computer:
|
||||
if ((!plane.control_mode->is_guided_mode()) &&
|
||||
if (!plane.control_mode->is_guided_or_adsb_mode() &&
|
||||
(plane.control_mode != &plane.mode_auto)) {
|
||||
// failed
|
||||
return MAV_RESULT_FAILED;
|
||||
|
|
|
@ -43,7 +43,7 @@ void Plane::fence_check()
|
|||
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
|
||||
case AC_FENCE_ACTION_RTL_AND_LAND:
|
||||
if (plane.control_mode_reason == ModeReason::FENCE_BREACHED &&
|
||||
control_mode->is_guided_mode()) {
|
||||
control_mode->is_guided_or_adsb_mode()) {
|
||||
set_mode(*previous_mode, ModeReason::FENCE_RETURN_PREVIOUS_MODE);
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -306,7 +306,7 @@ bool Mode::use_throttle_limits() const
|
|||
return !plane.g.throttle_passthru_stabilize;
|
||||
}
|
||||
|
||||
if (is_guided_mode() && plane.guided_throttle_passthru) {
|
||||
if (is_guided_or_adsb_mode() && plane.guided_throttle_passthru) {
|
||||
// manual pass through of throttle while in GUIDED
|
||||
return false;
|
||||
}
|
||||
|
@ -338,7 +338,7 @@ bool Mode::use_battery_compensation() const
|
|||
return false;
|
||||
}
|
||||
|
||||
if (is_guided_mode() && plane.guided_throttle_passthru) {
|
||||
if (is_guided_or_adsb_mode() && plane.guided_throttle_passthru) {
|
||||
// manual pass through of throttle while in GUIDED
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -103,6 +103,9 @@ public:
|
|||
virtual bool is_vtol_man_mode() const { return false; }
|
||||
|
||||
// guided or adsb mode
|
||||
virtual bool is_guided_or_adsb_mode() const { return is_guided_mode(); }
|
||||
|
||||
// guided mode
|
||||
virtual bool is_guided_mode() const { return false; }
|
||||
|
||||
// true if mode can have terrain following disabled by switch
|
||||
|
@ -617,7 +620,8 @@ public:
|
|||
|
||||
void navigate() override;
|
||||
|
||||
virtual bool is_guided_mode() const override { return true; }
|
||||
// guided or adsb mode
|
||||
virtual bool is_guided_or_adsb_mode() const override { return true; }
|
||||
|
||||
bool does_auto_throttle() const override { return true; }
|
||||
|
||||
|
|
|
@ -359,7 +359,7 @@ void Plane::update_loiter(uint16_t radius)
|
|||
auto_state.wp_proportion > 1) {
|
||||
// we've reached the target, start the timer
|
||||
loiter.start_time_ms = millis();
|
||||
if (control_mode->is_guided_mode()) {
|
||||
if (control_mode->is_guided_or_adsb_mode()) {
|
||||
// starting a loiter in GUIDED means we just reached the target point
|
||||
gcs().send_mission_item_reached_message(0);
|
||||
}
|
||||
|
|
|
@ -1303,7 +1303,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
|||
|
||||
if ((plane.g.stick_mixing == StickMixing::NONE) &&
|
||||
(plane.control_mode == &plane.mode_qrtl ||
|
||||
plane.control_mode->is_guided_mode() ||
|
||||
plane.control_mode->is_guided_or_adsb_mode() ||
|
||||
in_vtol_auto())) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -2077,7 +2077,7 @@ bool QuadPlane::in_vtol_mode(void) const
|
|||
if (plane.control_mode->is_vtol_mode()) {
|
||||
return true;
|
||||
}
|
||||
if (plane.control_mode->is_guided_mode()
|
||||
if (plane.control_mode->is_guided_or_adsb_mode()
|
||||
&& plane.auto_state.vtol_loiter &&
|
||||
poscontrol.get_state() > QPOS_APPROACH) {
|
||||
return true;
|
||||
|
@ -2108,7 +2108,7 @@ bool QuadPlane::in_vtol_posvel_mode(void) const
|
|||
#if QAUTOTUNE_ENABLED
|
||||
plane.control_mode == &plane.mode_qautotune ||
|
||||
#endif
|
||||
(plane.control_mode->is_guided_mode() &&
|
||||
(plane.control_mode->is_guided_or_adsb_mode() &&
|
||||
plane.auto_state.vtol_loiter &&
|
||||
poscontrol.get_state() > QPOS_APPROACH) ||
|
||||
in_vtol_auto());
|
||||
|
|
Loading…
Reference in New Issue