Skip to content

Comments

Add tailsitter heading alignment phase during forward transition (Pr yaw alignment)#39

Open
Tarun24-airbound wants to merge 32 commits intoairbound-developfrom
pr-yaw_alignment
Open

Add tailsitter heading alignment phase during forward transition (Pr yaw alignment)#39
Tarun24-airbound wants to merge 32 commits intoairbound-developfrom
pr-yaw_alignment

Conversation

@Tarun24-airbound
Copy link

@Tarun24-airbound Tarun24-airbound commented Feb 6, 2026

Implements a pre-transition alignment phase for tailsitter aircraft that ensures proper heading alignment before proceeding with the forward transition. The aircraft will automatically yaw to match the target bearing and hold position for 2 seconds before transitioning, preventing premature transitions that could cause instability.

Key Features

  • Blocks transition until heading error is within 10° and yaw rate is below 3°/s
  • 2-second stabilization wait after alignment is achieved
  • 10-second timeout to prevent indefinite blocking
  • One-shot logic prevents re-triggering during the same transition attempt
  • Disables weathervane during alignment for predictable yaw control
  • Maintains altitude hold and provides status logging during alignment

##Reference

https://www.notion.so/airbound/Heading-alignment-to-WP-2-before-transition-2f121adf4be9802bb36acd78519f64de?source=copy_link

Summary by CodeRabbit

Release Notes

  • New Features

    • Automatic yaw alignment system for tailsitter aircraft during transitions with bearing and yaw rate monitoring
    • Enhanced attitude data logging including pitch compensation and axis-angle representations for improved diagnostics
    • Improved automatic door control logic for landing phases with manual override capability
  • Chores

    • Updated dependency library
    • Firmware version tagged as hotfix with auto yaw alignment feature

akshar-airbound and others added 30 commits December 31, 2025 11:35
- Update version.h to rc4
- Update default params in lua scripts
@coderabbitai
Copy link

coderabbitai bot commented Feb 6, 2026

Important

Review skipped

Auto reviews are disabled on base/target branches other than the default branch.

Please check the settings in the CodeRabbit UI or the .coderabbit.yaml file in this repository. To trigger a single review, invoke the @coderabbitai review command.

You can disable this status message by setting the reviews.review_status to false in the CodeRabbit configuration file.

  • ✅ Full review completed - (🔄 Check again to review again)
✨ Finishing touches
🧪 Generate unit tests (beta)
  • Create PR with unit tests
  • Post copyable unit tests in a comment
  • Commit unit tests in branch pr-yaw_alignment

Thanks for using CodeRabbit! It's free for OSS, and your support helps us grow. If you like it, consider giving us a shout-out.

❤️ Share

Comment @coderabbitai help to get the list of available commands and usage tips.

Copy link

@coderabbitai coderabbitai bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actionable comments posted: 4

🤖 Fix all issues with AI agents
In `@ArduPlane/tailsitter.cpp`:
- Around line 924-972: The timeout start (align_phase_start_ms) is set
unconditionally on detecting a "new attempt" which can expire before alignment
actually becomes active; change the logic so align_phase_start_ms is only
initialized when alignment is actually active (should_run_alignment == true) —
e.g., on the new-attempt branch do not set align_phase_start_ms unconditionally
but only set it when should_run_alignment is true (or set it to 0/clear it when
should_run_alignment is false), and ensure you detect the transition from
inactive->active to start the timer (use last_run_ms and
alignment_completed_for_this_flight to gate this), updating the places that use
align_phase_start_ms, timeout_expired, and WAIT_DELAY_MS accordingly.

In `@libraries/AC_AttitudeControl/AC_AttitudeControl.h`:
- Around line 229-234: relax_attitude_controllers() currently initializes
_attitude_target and _attitude_ang_error but leaves _attitude_body
uninitialized, which can cause get_attitude_body_quat() to return garbage during
early startup; update relax_attitude_controllers() to set _attitude_body =
_attitude_target (matching the pattern used for _attitude_target and
_attitude_ang_error) so _attitude_body has a valid value before
attitude_controller_run_quat() runs and before get_attitude_body_quat() or
logging uses it.

In
`@libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/scripts/ab_door_auto_control.lua`:
- Around line 90-92: The OVERRIDE parameter (declared with
param:add_param(PARAM_TABLE_KEY, PARAM_IDX.OVERRIDE, "OVERRIDE", 0)) currently
only affects manual timeout but does not stop automatic behavior; fix by reading
the OVERRIDE param value wherever auto mode is triggered and skip calling
run_auto_mode() when OVERRIDE==1. Update both places that invoke run_auto_mode()
to first check the parameter (using the same PARAM_TABLE_KEY and
PARAM_IDX.OVERRIDE lookup method used elsewhere) and return/continue without
running auto logic if the override is set.

In `@modules/littlefs`:
- Line 1: Add a new submodule entry for modules/littlefs to the .gitmodules file
so CI can initialize the submodule; specifically, add a [submodule
"modules/littlefs"] section containing path = modules/littlefs and url =
<repository-url> (replace <repository-url> with the actual littlefs repo URL).
Ensure the entry exactly matches the submodule path "modules/littlefs" and
commit the updated .gitmodules so git submodule update succeeds.

Comment on lines +924 to +972
// Static Variables (State Tracking)
static uint32_t align_phase_start_ms = 0;
static uint32_t alignment_done_ms = 0;
static uint32_t last_run_ms = 0;
static uint32_t last_log_ms = 0;
// NEW: One-Shot Flag to prevent infinite loops
static bool alignment_completed_for_this_flight = false;

// --- DETECT NEW FLIGHT/TRANSITION ENTRY ---
// If this function hasn't run for >200ms, assume it's a new attempt.
if (now_ - last_run_ms > 200) {
align_phase_start_ms = now_;
alignment_done_ms = 0;
last_log_ms = 0;
alignment_completed_for_this_flight = false; // Reset flag for new transition
}
last_run_ms = now_;

// Check Validity & Only run if we haven't finished aligning yet
bool should_run_alignment = !alignment_completed_for_this_flight &&
(plane.control_mode == &plane.mode_auto || plane.control_mode == &plane.mode_guided) &&
(plane.nav_controller != nullptr);

if (should_run_alignment) {
// Disable weathervane during alignment
if (quadplane.weathervane != nullptr) {
quadplane.weathervane->allow_weathervaning(false);
}

int32_t target_bearing_cd = plane.nav_controller->target_bearing_cd();
int32_t current_yaw_cd = quadplane.ahrs.yaw_sensor;
int32_t error_cd = wrap_180_cd(target_bearing_cd - current_yaw_cd);
Vector3f gyro = quadplane.ahrs.get_gyro();
float yaw_rate_deg = degrees(gyro.z);

// LOGIC: Are we aligned right now?
bool is_aligned = (abs(error_cd) <= ALIGN_TOLERANCE_CD) && (abs(yaw_rate_deg) <= MAX_SPIN_RATE_DEG);

// TIMER LOGIC
if (is_aligned) {
if (alignment_done_ms == 0) alignment_done_ms = now_;
} else {
alignment_done_ms = 0; // Reset if we drift out
}

// EXIT CRITERIA
bool wait_complete = (alignment_done_ms != 0) && (now_ - alignment_done_ms >= WAIT_DELAY_MS);
bool timeout_expired = (now_ - align_phase_start_ms >= ALIGN_PHASE_LIMIT_MS);

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue | 🟡 Minor

Start the alignment timeout only when alignment is actually active.
align_phase_start_ms is set on entry regardless of should_run_alignment. If the vehicle enters TRANSITION_ANGLE_WAIT_FW in a non-AUTO/GUIDED mode and later switches into AUTO/GUIDED, the timeout can already be expired, causing alignment to be skipped immediately. Consider arming the timer when alignment becomes active (or clearing it while inactive).

💡 One way to gate the timer
-            // --- DETECT NEW FLIGHT/TRANSITION ENTRY ---
-            // If this function hasn't run for >200ms, assume it's a new attempt.
+            // --- DETECT NEW FLIGHT/TRANSITION ENTRY ---
             if (now_ - last_run_ms > 200) {
                 align_phase_start_ms = now_;
                 alignment_done_ms = 0;
                 last_log_ms = 0;
                 alignment_completed_for_this_flight = false; // Reset flag for new transition
             }
             last_run_ms = now_;

             // Check Validity & Only run if we haven't finished aligning yet
             bool should_run_alignment = !alignment_completed_for_this_flight &&
                                         (plane.control_mode == &plane.mode_auto || plane.control_mode == &plane.mode_guided) &&
                                         (plane.nav_controller != nullptr);
+
+            if (!should_run_alignment) {
+                align_phase_start_ms = 0;
+                alignment_done_ms = 0;
+            } else if (align_phase_start_ms == 0) {
+                align_phase_start_ms = now_;
+            }
🤖 Prompt for AI Agents
In `@ArduPlane/tailsitter.cpp` around lines 924 - 972, The timeout start
(align_phase_start_ms) is set unconditionally on detecting a "new attempt" which
can expire before alignment actually becomes active; change the logic so
align_phase_start_ms is only initialized when alignment is actually active
(should_run_alignment == true) — e.g., on the new-attempt branch do not set
align_phase_start_ms unconditionally but only set it when should_run_alignment
is true (or set it to 0/clear it when should_run_alignment is false), and ensure
you detect the transition from inactive->active to start the timer (use
last_run_ms and alignment_completed_for_this_flight to gate this), updating the
places that use align_phase_start_ms, timeout_expired, and WAIT_DELAY_MS
accordingly.

Comment on lines +229 to +234
// Return the body-to-NED error attitude used by the quadplane-specific attitude control input methods
Quaternion get_attitude_error_quat() const { return _attitude_ang_error; }

// Return the body-to-NED attitude used by the quadplane-specific attitude control input methods
Quaternion get_attitude_body_quat() const { return _attitude_body; }

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue | 🟡 Minor

🧩 Analysis chain

🏁 Script executed:

fd -t f "AC_AttitudeControl" | head -20

Repository: AirboundInc/ardupilot

Length of output: 734


🏁 Script executed:

find . -name "*.h" -o -name "*.cpp" | xargs grep -l "AC_AttitudeControl" | grep -E "AC_AttitudeControl\.(h|cpp)$"

Repository: AirboundInc/ardupilot

Length of output: 170


🏁 Script executed:

git ls-files | grep -i "attitude" | grep -E "\.(h|cpp)$"

Repository: AirboundInc/ardupilot

Length of output: 1220


🏁 Script executed:

wc -l libraries/AC_AttitudeControl/AC_AttitudeControl.h

Repository: AirboundInc/ardupilot

Length of output: 118


🏁 Script executed:

sed -n '220,240p' libraries/AC_AttitudeControl/AC_AttitudeControl.h

Repository: AirboundInc/ardupilot

Length of output: 1262


🏁 Script executed:

sed -n '500,520p' libraries/AC_AttitudeControl/AC_AttitudeControl.h

Repository: AirboundInc/ardupilot

Length of output: 1017


🏁 Script executed:

grep -n "AC_AttitudeControl::AC_AttitudeControl" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | head -5

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

grep -n "relax_attitude_controllers" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 122


🏁 Script executed:

grep -n "attitude_controller_run_quat" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 561


🏁 Script executed:

sed -n '168,190p' libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 840


🏁 Script executed:

sed -n '708,750p' libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 2304


🏁 Script executed:

grep -n "_attitude_body" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | head -20

Repository: AirboundInc/ardupilot

Length of output: 104


🏁 Script executed:

sed -n '750,760p' libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 515


🏁 Script executed:

grep -n "get_attitude_body_quat\|get_attitude_target_quat\|get_attitude_error_quat" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

grep -rn "get_attitude_body_quat" --include="*.cpp" --include="*.h" | head -20

Repository: AirboundInc/ardupilot

Length of output: 307


🏁 Script executed:

grep -n "AC_AttitudeControl::" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | grep -E "(constructor|AC_AttitudeControl\()" | head -5

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

sed -n '1,100p' libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | grep -A 20 "AC_AttitudeControl::"

Repository: AirboundInc/ardupilot

Length of output: 907


🏁 Script executed:

cat libraries/AC_AttitudeControl/AC_AttitudeControl.h | grep -A 5 "class AC_AttitudeControl"

Repository: AirboundInc/ardupilot

Length of output: 570


🏁 Script executed:

grep -n "Quaternion.*initialise\|Quaternion()" libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | head -10

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

sed -n '1,50p' libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | grep -A 30 "AC_AttitudeControl::" | head -40

Repository: AirboundInc/ardupilot

Length of output: 1296


🏁 Script executed:

grep -n "AC_AttitudeControl.*{" libraries/AC_AttitudeControl/AC_AttitudeControl.h | head -5

Repository: AirboundInc/ardupilot

Length of output: 190


🏁 Script executed:

sed -n '1,100p' libraries/AC_AttitudeControl/AC_AttitudeControl.h | grep -A 50 "AC_AttitudeControl("

Repository: AirboundInc/ardupilot

Length of output: 2361


Initialize _attitude_body in relax_attitude_controllers() to ensure valid state before first use.

The getter get_attitude_body_quat() may be called before attitude_controller_run_quat() has executed (e.g., during early logging in startup), but _attitude_body is only assigned within attitude_controller_run_quat() at line 756. Unlike _attitude_target and _attitude_ang_error, which are explicitly initialized in relax_attitude_controllers(), _attitude_body is left uninitialized. The getter is already in use (ArduPlane/Log.cpp:27) and could return an uninitialized quaternion.

Add _attitude_body = _attitude_target; in relax_attitude_controllers() after line 172 to match the initialization pattern of other attitude members:

Suggested initialization
 void AC_AttitudeControl::relax_attitude_controllers()
 {
     // Initialize the attitude variables to the current attitude
     _ahrs.get_quat_body_to_ned(_attitude_target);
     _attitude_target.to_euler(_euler_angle_target);
     _attitude_ang_error.initialise();
+    _attitude_body = _attitude_target;
📝 Committable suggestion

‼️ IMPORTANT
Carefully review the code before committing. Ensure that it accurately replaces the highlighted code, contains no missing lines, and has no issues with indentation. Thoroughly test & benchmark the code to ensure it meets the requirements.

Suggested change
// Return the body-to-NED error attitude used by the quadplane-specific attitude control input methods
Quaternion get_attitude_error_quat() const { return _attitude_ang_error; }
// Return the body-to-NED attitude used by the quadplane-specific attitude control input methods
Quaternion get_attitude_body_quat() const { return _attitude_body; }
void AC_AttitudeControl::relax_attitude_controllers()
{
// Initialize the attitude variables to the current attitude
_ahrs.get_quat_body_to_ned(_attitude_target);
_attitude_target.to_euler(_euler_angle_target);
_attitude_ang_error.initialise();
_attitude_body = _attitude_target;
}
🤖 Prompt for AI Agents
In `@libraries/AC_AttitudeControl/AC_AttitudeControl.h` around lines 229 - 234,
relax_attitude_controllers() currently initializes _attitude_target and
_attitude_ang_error but leaves _attitude_body uninitialized, which can cause
get_attitude_body_quat() to return garbage during early startup; update
relax_attitude_controllers() to set _attitude_body = _attitude_target (matching
the pattern used for _attitude_target and _attitude_ang_error) so _attitude_body
has a valid value before attitude_controller_run_quat() runs and before
get_attitude_body_quat() or logging uses it.

Comment on lines +90 to +92
-- Override parameter definition
--[[ @Param: DOOR_OVERRIDE, @DisplayName: Door Servo override, @Description: Enable/Disable for doors script auto logic, @Range: 0 1 --]]
assert(param:add_param(PARAM_TABLE_KEY, PARAM_IDX.OVERRIDE, "OVERRIDE", 0))
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue | 🟠 Major

OVERRIDE param doesn’t actually disable auto logic.

The parameter description says it enables/disables auto logic, but the implementation only bypasses manual-override timeout; auto mode still runs when the RC hasn’t moved. Either update the description or gate run_auto_mode() when OVERRIDE=1.

🔧 Suggested fix to honor DOOR_OVERRIDE by skipping auto mode
-    if not check_manual_override() then
-        run_auto_mode()
-    end
+    local auto_disabled = (config.cache.man_override == 1)
+    if not check_manual_override() and not auto_disabled then
+        run_auto_mode()
+    end

Also applies to: 372-377

🤖 Prompt for AI Agents
In
`@libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/scripts/ab_door_auto_control.lua`
around lines 90 - 92, The OVERRIDE parameter (declared with
param:add_param(PARAM_TABLE_KEY, PARAM_IDX.OVERRIDE, "OVERRIDE", 0)) currently
only affects manual timeout but does not stop automatic behavior; fix by reading
the OVERRIDE param value wherever auto mode is triggered and skip calling
run_auto_mode() when OVERRIDE==1. Update both places that invoke run_auto_mode()
to first check the parameter (using the same PARAM_TABLE_KEY and
PARAM_IDX.OVERRIDE lookup method used elsewhere) and return/continue without
running auto logic if the override is set.

@@ -0,0 +1 @@
Subproject commit 34be692aafaaf4319a18e415b08aa4332697408b
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue | 🔴 Critical

🧩 Analysis chain

🏁 Script executed:

#!/bin/bash
# Verify .gitmodules contents and submodule configuration
echo "=== Contents of .gitmodules ==="
if [ -f .gitmodules ]; then
  cat .gitmodules
else
  echo ".gitmodules file not found"
fi

echo ""
echo "=== Submodule paths ==="
git config -f .gitmodules --get-regexp '^submodule\..*\.path$' 2>/dev/null || echo "No submodule paths found"

echo ""
echo "=== Submodule URLs ==="
git config -f .gitmodules --get-regexp '^submodule\..*\.url$' 2>/dev/null || echo "No submodule URLs found"

echo ""
echo "=== Check modules/littlefs specifically ==="
git config -f .gitmodules --get 'submodule.modules/littlefs.url' 2>/dev/null || echo "No entry for modules/littlefs"
git config -f .gitmodules --get 'submodule.modules/littlefs.path' 2>/dev/null || echo "No path entry for modules/littlefs"

Repository: AirboundInc/ardupilot

Length of output: 3603


Add modules/littlefs entry to .gitmodules to unblock CI submodule initialization.

The .gitmodules file is missing a configuration entry for modules/littlefs, but the submodule pointer in the working tree has been updated. This will cause CI to fail during git submodule update with "fatal: No url found for submodule path 'modules/littlefs' in .gitmodules". Add the following entry to .gitmodules:

[submodule "modules/littlefs"]
	path = modules/littlefs
	url = <repository-url>

Replace <repository-url> with the appropriate littlefs repository URL.

🧰 Tools
🪛 GitHub Actions: test chibios

[error] 1-1: Submodule update failed. Command 'git -c protocol.version=2 submodule update --init --force --depth=1 --recursive' reported: fatal: No url found for submodule path 'modules/littlefs' in .gitmodules.

🪛 GitHub Actions: test Linux SBC

[error] 1-1: fatal: No url found for submodule path 'modules/littlefs' in .gitmodules. This occurred during 'git submodule update --init --force --depth=1 --recursive'.

🤖 Prompt for AI Agents
In `@modules/littlefs` at line 1, Add a new submodule entry for modules/littlefs
to the .gitmodules file so CI can initialize the submodule; specifically, add a
[submodule "modules/littlefs"] section containing path = modules/littlefs and
url = <repository-url> (replace <repository-url> with the actual littlefs repo
URL). Ensure the entry exactly matches the submodule path "modules/littlefs" and
commit the updated .gitmodules so git submodule update succeeds.

quadplane.pos_control->set_pos_target_z_from_climb_rate_cm(0.0f);

// Control
quadplane.pos_control->update_z_controller();
Copy link

@atharva-airbound atharva-airbound Feb 9, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We are manually calling update_z_controller() here but there is a comment in quadplane.cpp mentioning this shouldn't be done during transition

// never run Z controller in tailsitter transtion

Here is a relevant PR from when the comment was added: ArduPilot#19286
Needs investigation.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can try calling hold_hover(0) instead of running the position controllers to get the roll and pitch setpoints.

Will try this when I have time.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants