chore: rename to guided course

This commit is contained in:
mahima-yoga
2026-05-12 14:06:26 +02:00
parent 0e25bb9a6d
commit c7ca6cc2df
11 changed files with 24 additions and 24 deletions
+1 -1
View File
@@ -36,7 +36,7 @@ uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_POSITION_SLOW = 6
uint8 NAVIGATION_STATE_AUTO_COURSE = 7 # Course hold mode (FW: maintain course/alt/speed)
uint8 NAVIGATION_STATE_GUIDED_COURSE = 7 # Guided Course mode (FW: maintain course/alt/speed)
uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode
uint8 NAVIGATION_STATE_FREE3 = 9
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
+2 -2
View File
@@ -51,7 +51,7 @@ static inline uint32_t getValidNavStates()
(1u << vehicle_status_s::NAVIGATION_STATE_POSCTL) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE) |
(1u << vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) |
(1u << vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW) |
(1u << vehicle_status_s::NAVIGATION_STATE_ACRO) |
@@ -76,7 +76,7 @@ const char *const nav_state_names[vehicle_status_s::NAVIGATION_STATE_MAX] = {
"Hold",
"Return",
"Position Slow",
"Course",
"Guided Course",
"Altitude Cruise",
"9: unallocated",
"Acro",
+7 -7
View File
@@ -491,7 +491,7 @@ int Commander::custom_command(int argc, char *argv[])
} else if (!strcmp(argv[1], "auto:course")) {
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_SUB_MODE_AUTO_COURSE);
PX4_CUSTOM_SUB_MODE_GUIDED_COURSE);
} else if (!strcmp(argv[1], "auto:rtl")) {
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
@@ -879,9 +879,9 @@ Commander::handle_command(const vehicle_command_s &cmd)
// If already in course mode, stay in course mode (navigator handles any altitude update)
// Only switch to loiter if a specific lat/lon target is given, or we are not in course mode.
const bool has_position_target = PX4_ISFINITE(cmd.param5) && PX4_ISFINITE(cmd.param6);
const bool in_course_mode = _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE;
const bool in_course_mode = _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE;
const uint8_t target_state = (in_course_mode && !has_position_target)
? vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE
? vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE
: vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
if (_user_mode_intention.change(target_state, getSourceFromCommand(cmd))) {
@@ -903,8 +903,8 @@ Commander::handle_command(const vehicle_command_s &cmd)
// the data at the exact same time.
// If already in course hold, stay in course hold (navigator handles the altitude update)
uint8_t target_state = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE)
? vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE
uint8_t target_state = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE)
? vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE
: vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
if (_user_mode_intention.change(target_state)) {
@@ -987,8 +987,8 @@ Commander::handle_command(const vehicle_command_s &cmd)
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND;
break;
case PX4_CUSTOM_SUB_MODE_AUTO_COURSE:
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE;
case PX4_CUSTOM_SUB_MODE_GUIDED_COURSE:
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE;
break;
case PX4_CUSTOM_SUB_MODE_EXTERNAL1...PX4_CUSTOM_SUB_MODE_EXTERNAL8:
@@ -89,7 +89,7 @@ void getVehicleControlMode(uint8_t nav_state, uint8_t vehicle_type,
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
case vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE:
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF:
vehicle_control_mode.flag_control_auto_enabled = true;
@@ -58,7 +58,7 @@ static inline navigation_mode_t navigation_mode(uint8_t nav_state)
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER: return navigation_mode_t::auto_loiter;
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE: return navigation_mode_t::auto_course;
case vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE: return navigation_mode_t::auto_course;
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: return navigation_mode_t::auto_rtl;
@@ -123,13 +123,13 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags)
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER, flags.mode_req_wind_and_flight_time_compliance);
// NAVIGATION_STATE_AUTO_COURSE
// NAVIGATION_STATE_GUIDED_COURSE
// Heading mode is GPS-independent, course mode internally checks for GPS availability.
// Only require attitude and altitude, not global position.
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_angular_velocity);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_attitude);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_wind_and_flight_time_compliance);
setRequirement(vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE, flags.mode_req_angular_velocity);
setRequirement(vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE, flags.mode_req_attitude);
setRequirement(vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE, flags.mode_req_wind_and_flight_time_compliance);
// NAVIGATION_STATE_AUTO_RTL
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_angular_velocity);
+1 -1
View File
@@ -509,7 +509,7 @@ bool Failsafe::isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_m
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
case vehicle_status_s::NAVIGATION_STATE_ORBIT:
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
case vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE:
return exception_mask_parameter & (int)LinkLossExceptionBits::AutoModes;
case vehicle_status_s::NAVIGATION_STATE_OFFBOARD:
+3 -3
View File
@@ -66,7 +66,7 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET,
PX4_CUSTOM_SUB_MODE_AUTO_PRECLAND,
PX4_CUSTOM_SUB_MODE_AUTO_VTOL_TAKEOFF,
PX4_CUSTOM_SUB_MODE_AUTO_COURSE,
PX4_CUSTOM_SUB_MODE_GUIDED_COURSE,
PX4_CUSTOM_SUB_MODE_EXTERNAL1,
PX4_CUSTOM_SUB_MODE_EXTERNAL2,
PX4_CUSTOM_SUB_MODE_EXTERNAL3,
@@ -193,9 +193,9 @@ static inline union px4_custom_mode get_px4_custom_mode(uint8_t nav_state)
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_VTOL_TAKEOFF;
break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
case vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE:
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_COURSE;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_GUIDED_COURSE;
break;
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL1:
@@ -144,7 +144,7 @@ private:
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL);
+1 -1
View File
@@ -42,7 +42,7 @@
#include <matrix/math.hpp>
Course::Course(Navigator *navigator) :
MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE)
MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE)
{
}
+1 -1
View File
@@ -856,7 +856,7 @@ void Navigator::run()
navigation_mode_new = &_loiter;
break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
case vehicle_status_s::NAVIGATION_STATE_GUIDED_COURSE:
_pos_sp_triplet_published_invalid_once = false;
navigation_mode_new = &_course;
break;