diff --git a/msg/RtlStatus.msg b/msg/RtlStatus.msg
index f25b22243a..271354fa9e 100644
--- a/msg/RtlStatus.msg
+++ b/msg/RtlStatus.msg
@@ -6,7 +6,7 @@ bool is_evaluation_pending # flag if the RTL point needs reevaluation (e.
bool has_vtol_approach # flag if approaches are defined for current RTL_TYPE parameter setting
uint8 rtl_type # Type of RTL chosen
-uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode
+uint8 safe_point_index # index of the chosen safe point, UINT8_MAX if no rally point was chosen
uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position
diff --git a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt
index e313921d82..ad18a2ad79 100644
--- a/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt
+++ b/src/modules/commander/HealthAndArmingChecks/CMakeLists.txt
@@ -56,6 +56,7 @@ px4_add_library(health_and_arming_checks
checks/manualControlCheck.cpp
checks/missionCheck.cpp
checks/modeCheck.cpp
+ checks/rallyPointCheck.cpp
checks/navigatorCheck.cpp
checks/offboardCheck.cpp
checks/openDroneIDCheck.cpp
diff --git a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp
index 53e9a5a534..5a5e5fb119 100644
--- a/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp
+++ b/src/modules/commander/HealthAndArmingChecks/HealthAndArmingChecks.hpp
@@ -68,6 +68,7 @@
#include "checks/geofenceCheck.hpp"
#include "checks/flightTimeCheck.hpp"
#include "checks/missionCheck.hpp"
+#include "checks/rallyPointCheck.hpp"
#include "checks/rcAndDataLinkCheck.hpp"
#include "checks/vtolCheck.hpp"
#include "checks/offboardCheck.hpp"
@@ -158,6 +159,7 @@ private:
GeofenceChecks _geofence_checks;
FlightTimeChecks _flight_time_checks;
MissionChecks _mission_checks;
+ RallyPointChecks _rally_point_checks;
RcAndDataLinkChecks _rc_and_data_link_checks;
VtolChecks _vtol_checks;
OffboardChecks _offboard_checks;
@@ -166,7 +168,7 @@ private:
ExternalChecks _external_checks;
#endif
- HealthAndArmingCheckBase *_checks[40] = {
+ HealthAndArmingCheckBase *_checks[41] = {
#ifndef CONSTRAINED_FLASH
&_external_checks,
#endif
@@ -188,6 +190,7 @@ private:
&_manual_control_checks,
&_home_position_checks,
&_mission_checks,
+ &_rally_point_checks,
&_offboard_checks, // must be after _estimator_checks
&_mode_checks, // must be after _estimator_checks, _home_position_checks, _mission_checks, _offboard_checks, _external_checks
&_open_drone_id_checks,
diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.cpp
new file mode 100644
index 0000000000..09c68738d1
--- /dev/null
+++ b/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.cpp
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2026 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include "rallyPointCheck.hpp"
+
+RallyPointChecks::RallyPointChecks()
+ : _param_rtl_type_handle(param_find("RTL_TYPE"))
+{
+}
+
+void RallyPointChecks::checkAndReport(const Context &context, Report &reporter)
+{
+ int32_t rtl_type = 0;
+
+ if (param_get(_param_rtl_type_handle, &rtl_type) != 0 || rtl_type != 5) {
+ // Only enforce rally point requirement when RTL_TYPE == 5 (safe points only)
+ return;
+ }
+
+ rtl_status_s rtl_status;
+
+ if (!_rtl_status_sub.copy(&rtl_status) || rtl_status.safe_point_index == UINT8_MAX) {
+ /* EVENT
+ * @description
+ * Upload at least one rally point before arming, or change RTL_TYPE.
+ *
+ *
+ * This check is active when RTL_TYPE is set to 5 (safe points only).
+ *
+ */
+ reporter.armingCheckFailure(NavModes::All, health_component_t::system,
+ events::ID("check_rally_point_missing"),
+ events::Log::Error, "No rally point available");
+
+ if (reporter.mavlink_log_pub()) {
+ mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: No rally point available\t");
+ }
+ }
+}
diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.hpp
new file mode 100644
index 0000000000..b36d6a7c2e
--- /dev/null
+++ b/src/modules/commander/HealthAndArmingChecks/checks/rallyPointCheck.hpp
@@ -0,0 +1,53 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2026 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "../Common.hpp"
+
+#include
+#include
+#include
+
+class RallyPointChecks : public HealthAndArmingCheckBase
+{
+public:
+ RallyPointChecks();
+ ~RallyPointChecks() = default;
+
+ void checkAndReport(const Context &context, Report &reporter) override;
+
+private:
+ uORB::Subscription _rtl_status_sub{ORB_ID(rtl_status)};
+
+ const param_t _param_rtl_type_handle;
+};
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
index 468d7e9e78..cf32daabb0 100644
--- a/src/modules/navigator/rtl.cpp
+++ b/src/modules/navigator/rtl.cpp
@@ -441,11 +441,16 @@ PositionYawSetpoint RTL::findClosestSafePoint(float min_dist, uint8_t &safe_poin
continue;
}
+ // Only look at rally points
+ if (mission_safe_point.nav_cmd != NAV_CMD_RALLY_POINT) {
+ continue;
+ }
+
// Ignore safepoints which are too close to the homepoint (only if home is an option to return to)
const bool far_from_home = get_distance_to_next_waypoint(_home_pos_sub.get().lat, _home_pos_sub.get().lon,
mission_safe_point.lat, mission_safe_point.lon) > MAX_DIST_FROM_HOME_FOR_LAND_APPROACHES;
- if (mission_safe_point.nav_cmd == NAV_CMD_RALLY_POINT && (far_from_home || (_param_rtl_type.get() == 5))) {
+ if (far_from_home || (_param_rtl_type.get() == 5)) {
const float dist{get_distance_to_next_waypoint(_global_pos_sub.get().lat, _global_pos_sub.get().lon, mission_safe_point.lat, mission_safe_point.lon)};
PositionYawSetpoint safepoint_position;