Navigator: rename WORK_ITEM_TYPE_ALIGN to WORK_ITEM_TYPE_ALIGN_HEADING

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer
2023-07-04 11:44:34 +02:00
parent 18e47f9b65
commit 15641f62d2
2 changed files with 6 additions and 6 deletions
+5 -5
View File
@@ -336,7 +336,7 @@ Mission::on_active()
|| _mission_item.nav_cmd == NAV_CMD_DO_VTOL_TRANSITION
|| _mission_item.nav_cmd == NAV_CMD_LAND
|| _mission_item.nav_cmd == NAV_CMD_VTOL_LAND
|| _work_item_type == WORK_ITEM_TYPE_ALIGN)) {
|| _work_item_type == WORK_ITEM_TYPE_ALIGN_HEADING)) {
// Mount control is disabled If the vehicle is in ROI-mode, the vehicle
// needs to rotate such that ROI is in the field of view.
// ROI only makes sense for multicopters.
@@ -960,7 +960,7 @@ Mission::set_mission_items()
_mission_item.force_heading = true;
new_work_item_type = WORK_ITEM_TYPE_ALIGN;
new_work_item_type = WORK_ITEM_TYPE_ALIGN_HEADING;
/* set position setpoint to current while aligning */
_mission_item.lat = _navigator->get_global_position()->lat;
@@ -969,7 +969,7 @@ Mission::set_mission_items()
/* heading is aligned now, prepare transition */
if (_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF &&
_work_item_type == WORK_ITEM_TYPE_ALIGN &&
_work_item_type == WORK_ITEM_TYPE_ALIGN_HEADING &&
_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING &&
!_navigator->get_land_detected()->landed) {
@@ -1175,7 +1175,7 @@ Mission::set_mission_items()
/* disable weathervane before front transition for allowing yaw to align */
pos_sp_triplet->current.disable_weather_vane = true;
new_work_item_type = WORK_ITEM_TYPE_ALIGN;
new_work_item_type = WORK_ITEM_TYPE_ALIGN_HEADING;
set_align_mission_item(&_mission_item, &mission_item_next_position);
@@ -1185,7 +1185,7 @@ Mission::set_mission_items()
}
/* yaw is aligned now */
if (_work_item_type == WORK_ITEM_TYPE_ALIGN &&
if (_work_item_type == WORK_ITEM_TYPE_ALIGN_HEADING &&
new_work_item_type == WORK_ITEM_TYPE_DEFAULT) {
new_work_item_type = WORK_ITEM_TYPE_DEFAULT;
+1 -1
View File
@@ -358,7 +358,7 @@ private:
WORK_ITEM_TYPE_DEFAULT, /**< default mission item */
WORK_ITEM_TYPE_TAKEOFF, /**< takeoff before moving to waypoint */
WORK_ITEM_TYPE_MOVE_TO_LAND, /**< move to land waypoint before descent */
WORK_ITEM_TYPE_ALIGN, /**< align for next waypoint */
WORK_ITEM_TYPE_ALIGN_HEADING, /**< align heading for next waypoint */
WORK_ITEM_TYPE_TRANSITION_AFTER_TAKEOFF,
WORK_ITEM_TYPE_MOVE_TO_LAND_AFTER_TRANSITION,
WORK_ITEM_TYPE_PRECISION_LAND