fix: rename Course Hold to Course

This commit is contained in:
ttechnick
2026-04-21 16:11:52 +02:00
committed by mahima-yoga
parent 596abdaba6
commit 7f88ec1232
15 changed files with 59 additions and 59 deletions
+1 -1
View File
@@ -127,7 +127,7 @@ uint8 FUSION_SOURCE_RNGBCN = 8 # Ranging Beacon
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # Start of PX4 internal only vehicle commands (> UINT16_MAX).
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Unused|Unused|Unused|Unused|Latitude (WGS-84)|Longitude (WGS-84)|[m] Altitude (AMSL from GNSS, positive above ground)|
uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Unused|Unused|Unused|Unused|Unused|Unused|
uint32 VEHICLE_CMD_DO_CHANGE_COURSE = 100002 # Change the course setpoint in Course Hold mode. |[rad] Course (bearing) [-PI..PI, NaN = no change]|Unused|Unused|Unused|Unused|Unused|Unused|
uint32 VEHICLE_CMD_DO_CHANGE_COURSE = 100002 # Change the course setpoint in Course mode. |[rad] Course (bearing) [-PI..PI, NaN = no change]|Unused|Unused|Unused|Unused|Unused|Unused|
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization.
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.
+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_HOLD = 7 # Course hold mode (FW: maintain course/alt/speed)
uint8 NAVIGATION_STATE_AUTO_COURSE = 7 # Course hold 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
@@ -593,8 +593,8 @@
"description": "Altitude Cruise"
},
"25": {
"name": "auto_course_hold",
"description": "Course Hold"
"name": "auto_course",
"description": "Course"
},
"255": {
"name": "unknown",
+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_HOLD) |
(1u << vehicle_status_s::NAVIGATION_STATE_AUTO_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 Hold",
"Course",
"Altitude Cruise",
"9: unallocated",
"Acro",
+8 -8
View File
@@ -489,9 +489,9 @@ int Commander::custom_command(int argc, char *argv[])
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_SUB_MODE_AUTO_LOITER);
} else if (!strcmp(argv[1], "auto:course_hold")) {
} 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_HOLD);
PX4_CUSTOM_SUB_MODE_AUTO_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,
@@ -895,8 +895,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_HOLD)
? vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD
uint8_t target_state = (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE)
? vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE
: vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER;
if (_user_mode_intention.change(target_state)) {
@@ -911,7 +911,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;
case vehicle_command_s::VEHICLE_CMD_DO_CHANGE_COURSE: {
// DO_CHANGE_COURSE is only valid in course hold mode, navigator handles the actual course update
// DO_CHANGE_COURSE is only valid in course mode, navigator handles the actual course update
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
}
break;
@@ -979,8 +979,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_HOLD:
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD;
case PX4_CUSTOM_SUB_MODE_AUTO_COURSE:
desired_nav_state = vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE;
break;
case PX4_CUSTOM_SUB_MODE_EXTERNAL1...PX4_CUSTOM_SUB_MODE_EXTERNAL8:
@@ -3236,7 +3236,7 @@ The commander module contains the state machine for mode switching and failsafe
PRINT_MODULE_USAGE_COMMAND("land");
PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition");
PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode");
PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1",
PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow|auto:mission|auto:loiter|auto:course|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1",
"Flight mode", false);
PRINT_MODULE_USAGE_COMMAND("pair");
PRINT_MODULE_USAGE_COMMAND("termination");
@@ -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_HOLD:
case vehicle_status_s::NAVIGATION_STATE_AUTO_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_HOLD: return navigation_mode_t::auto_course_hold;
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE: return navigation_mode_t::auto_course;
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: return navigation_mode_t::auto_rtl;
@@ -123,21 +123,21 @@ 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_HOLD (same requirements as AUTO_LOITER)
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_angular_velocity);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_attitude);
// NAVIGATION_STATE_AUTO_COURSE (same requirements as AUTO_LOITER)
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);
if (vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) {
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_global_position_relaxed);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_local_position_relaxed);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_global_position_relaxed);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_local_position_relaxed);
} else {
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_global_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_local_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_global_position);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE, flags.mode_req_local_position);
}
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_local_alt);
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD, flags.mode_req_wind_and_flight_time_compliance);
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);
// NAVIGATION_STATE_AUTO_RTL
setRequirement(vehicle_status_s::NAVIGATION_STATE_AUTO_RTL, flags.mode_req_angular_velocity);
+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_HOLD,
PX4_CUSTOM_SUB_MODE_AUTO_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_HOLD:
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_COURSE_HOLD;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_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_HOLD
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_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
@@ -44,7 +44,7 @@ set(NAVIGATOR_SOURCES
mission_base.cpp
mission_block.cpp
mission.cpp
course_hold.cpp
course.cpp
loiter.cpp
rtl.cpp
rtl_direct.cpp
@@ -31,21 +31,21 @@
*
****************************************************************************/
/**
* @file course_hold.cpp
* @file course.cpp
*
* Course Hold mode: maintain constant course, altitude, and airspeed.
* Course mode: maintain constant course, altitude, and airspeed.
*/
#include "course_hold.h"
#include "course.h"
#include "navigator.h"
CourseHold::CourseHold(Navigator *navigator) :
MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD)
Course::Course(Navigator *navigator) :
MissionBlock(navigator, vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE)
{
}
void
CourseHold::on_activation()
Course::on_activation()
{
// Capture current state
_course = _navigator->get_local_position()->heading;
@@ -58,7 +58,7 @@ CourseHold::on_activation()
}
void
CourseHold::on_active()
Course::on_active()
{
// Check for incoming vehicle commands
// Commands are dispatched from navigator_main, which sets fields on this object
@@ -67,7 +67,7 @@ CourseHold::on_active()
}
void
CourseHold::update_course_setpoint()
Course::update_course_setpoint()
{
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
@@ -31,9 +31,9 @@
*
****************************************************************************/
/**
* @file course_hold.h
* @file course.h
*
* Course Hold mode: maintain constant course, altitude, and airspeed.
* Course mode: maintain constant course, altitude, and airspeed.
* Accepts DO_CHANGE_COURSE, DO_CHANGE_ALTITUDE, and DO_CHANGE_SPEED commands.
*/
@@ -42,11 +42,11 @@
#include "navigator_mode.h"
#include "mission_block.h"
class CourseHold : public MissionBlock
class Course : public MissionBlock
{
public:
CourseHold(Navigator *navigator);
~CourseHold() = default;
Course(Navigator *navigator);
~Course() = default;
void on_activation() override;
void on_active() override;
+3 -3
View File
@@ -41,7 +41,7 @@
#pragma once
#include "course_hold.h"
#include "course.h"
#include "geofence.h"
#include "land.h"
#include "precland.h"
@@ -177,7 +177,7 @@ public:
vehicle_status_s *get_vstatus() { return &_vstatus; }
PrecLand *get_precland() { return &_precland; } /**< allow others, e.g. Mission, to use the precision land block */
CourseHold *get_course_hold() { return &_course_hold; }
Course *get_course() { return &_course; }
const PositionYawSetpoint &get_last_pos_with_gcs_heartbeat() const { return _last_pos_with_gcs_heartbeat; }
@@ -388,7 +388,7 @@ private:
Land _land; /**< class for handling land commands */
PrecLand _precland; /**< class for handling precision land commands */
RTL _rtl; /**< class that handles RTL */
CourseHold _course_hold; /**< class that handles course hold */
Course _course; /**< class that handles course */
#if CONFIG_NAVIGATOR_ADSB
AdsbConflict _adsb_conflict; /**< class that handles ADSB conflict avoidance */
traffic_buffer_s _traffic_buffer{};
+13 -13
View File
@@ -81,7 +81,7 @@ Navigator::Navigator() :
_land(this),
_precland(this),
_rtl(this),
_course_hold(this)
_course(this)
{
/* Create a list of our possible navigation types */
_navigation_mode_array[0] = &_mission;
@@ -93,7 +93,7 @@ Navigator::Navigator() :
#if CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_navigation_mode_array[6] = &_vtol_takeoff;
#endif //CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF
_navigation_mode_array[7] = &_course_hold;
_navigation_mode_array[7] = &_course;
/* iterate through navigation modes and initialize _mission_item for each */
for (unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
@@ -432,10 +432,10 @@ void Navigator::run()
// only update the setpoint if armed, as it otherwise won't get executed until the vehicle switches to loiter,
// which can lead to dangerous and unexpected behaviors (see loiter.cpp, there is an if(armed) in there too)
if (_navigation_mode == &_course_hold) {
// In course hold mode, update altitude directly
if (_navigation_mode == &_course) {
// In course mode, update altitude directly
float new_alt = PX4_ISFINITE(cmd.param1) ? cmd.param1 : get_global_position()->alt;
_course_hold.set_altitude(new_alt);
_course.set_altitude(new_alt);
// DO_CHANGE_ALTITUDE is acknowledged by commander
} else {
@@ -514,8 +514,8 @@ void Navigator::run()
} else if (cmd.command == vehicle_command_s::VEHICLE_CMD_DO_CHANGE_COURSE
&& _vstatus.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
if (_navigation_mode == &_course_hold && PX4_ISFINITE(cmd.param1)) {
_course_hold.set_course(cmd.param1);
if (_navigation_mode == &_course && PX4_ISFINITE(cmd.param1)) {
_course.set_course(cmd.param1);
}
publish_vehicle_command_ack(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
@@ -723,15 +723,15 @@ void Navigator::run()
// XXX not differentiating ground and airspeed yet
set_cruising_speed(cmd.param2);
if (_navigation_mode == &_course_hold) {
_course_hold.set_airspeed(cmd.param2);
if (_navigation_mode == &_course) {
_course.set_airspeed(cmd.param2);
}
} else {
reset_cruising_speed();
if (_navigation_mode == &_course_hold) {
_course_hold.set_airspeed(-1.f);
if (_navigation_mode == &_course) {
_course.set_airspeed(-1.f);
}
/* if no speed target was given try to set throttle */
@@ -835,9 +835,9 @@ void Navigator::run()
navigation_mode_new = &_loiter;
break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE_HOLD:
case vehicle_status_s::NAVIGATION_STATE_AUTO_COURSE:
_pos_sp_triplet_published_invalid_once = false;
navigation_mode_new = &_course_hold;
navigation_mode_new = &_course;
break;
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: