Skip to content

Rotary Encoder Driver for Thrust Vectors#36

Open
anant3110 wants to merge 4 commits intoairbound-developfrom
pr-rotary-encoder-driver
Open

Rotary Encoder Driver for Thrust Vectors#36
anant3110 wants to merge 4 commits intoairbound-developfrom
pr-rotary-encoder-driver

Conversation

@anant3110
Copy link

@anant3110 anant3110 commented Jan 28, 2026

Add rotary encoder with quadrature architecture to measure angles

ISR based system called from HAL
Define in ArduPlane, with other sensors and servos
Add parameters to assign the appropriate pins and variables for the rotary encoder
Add synchronous modules that update a global instance at a fixed time
Add data flash logs as "RENC"

https://www.notion.so/airbound/Phi-Rotary-Encoders-on-Pixhawk-26f21adf4be9803e8c71ef67b8d1c1ee

Summary by CodeRabbit

New Features

  • Added rotary encoder support for tailsitter thrust vectoring, enabling configuration of two independent encoders with adjustable pins and counts-per-revolution settings. Includes telemetry logging of encoder positions and optional real-time GCS feedback for thrust vector angles.

✏️ Tip: You can customize this high-level summary in your review settings.

@coderabbitai
Copy link

coderabbitai bot commented Jan 28, 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)

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.

@anant3110 anant3110 requested a review from botmayank January 28, 2026 09:13
Copy link
Member

@botmayank botmayank left a comment

Choose a reason for hiding this comment

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

Overall lgtm, lets change version.h to show 4.5.7.3 - rc1 - rot_enc and add an autotest from rover if it can be adapted for this as a part of the ci/cd pipeline.

@botmayank
Copy link
Member

Discussed autotest addition will be added in the future, currently rover only supports wheel encoder adding which is non trivial at this point.

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: 10

🤖 Fix all issues with AI agents
In `@ArduPlane/tailsitter.h`:
- Around line 121-129: Remove or clarify the unused encoder parameter members
(encoder1_pin_a, encoder1_pin_b, encoder1_cpr, encoder2_pin_a, encoder2_pin_b,
encoder2_cpr) declared in tailsitter.h since AP_RotaryEncoder (rotary_encoder)
already exposes and uses its own parameters (RE_LA, RE_LB, RE_LC, RE_RA, RE_RB,
RE_RC); either delete these six AP_Int16 fields to avoid dead code and
confusion, or replace them with a clear comment above AP_RotaryEncoder
explaining that encoder configuration is handled by AP_RotaryEncoder and
referencing the RE_* parameter names so maintainers/users know which parameters
to use.

In `@libraries/AP_RotaryEncoder/AP_Quadrature.cpp`:
- Around line 83-89: The code assigns a floating-point degree value to
irq_state.angle (computed from irq_state.phase and
_frontend.get_counts_per_revolution) but irq_state.angle is declared as
uint32_t, causing precision loss and wrong values for negatives; update the
irq_state.angle declaration in the header (AP_Quadrature.h) to float (or
float32) so the computed value from irq_state.phase * (360.0f / cpr) is stored
correctly, and verify any code that reads irq_state.angle handles a float rather
than an unsigned integer.
- Around line 54-92: The irq_handler function currently performs non-ISR-safe
work: remove the GCS_SEND_TEXT call from irq_handler and any other blocking
calls (reference: irq_handler, GCS_SEND_TEXT), and instead record a minimal,
atomic error/event flag or push a small event into a lock-free/ISR-safe queue
(or set a volatile status bit) that a non-ISR task will consume and call
GCS_SEND_TEXT; also remove the useless static irq_count (or convert it to an
instance member if persistent per-instance counting is required) so the ISR only
updates ISR-safe state (e.g., irq_state.phase, irq_state.angle, irq_state.time)
and enqueues/flags any diagnostic messages for later processing.

In `@libraries/AP_RotaryEncoder/AP_Quadrature.h`:
- Around line 30-34: Change the IrqState struct so irq_state.angle uses a
floating type instead of uint32_t: update the declaration of struct IrqState
(the member named angle) from uint32_t to float to preserve fractional results
produced by the angle calculations and avoid precision loss in code that
reads/writes irq_state.angle.
- Around line 36-38: Initialize the member variables to avoid undefined
behavior: set _pinA and _pinB to UINT8_MAX instead of -1 for clarity and
initialize A_value and B_value (e.g., 0) in the AP_Quadrature class member
declarations so an interrupt won’t read garbage before update_pin() runs; ensure
the ISR and any lookup/index computation that reads A_value/B_value will use the
initialized values.
- Around line 24-28: The header declares pin_ab_to_phase(bool pin_a, bool pin_b)
and update_phase_and_error_count() but they are missing in AP_Quadrature.cpp;
either remove those declarations from AP_Quadrature.h or add implementations in
AP_Quadrature.cpp: implement pin_ab_to_phase to map the two input booleans into
a 2-bit phase value (0..3) consistently with the rest of the class, and
implement update_phase_and_error_count to read current pin states, compute new
phase via pin_ab_to_phase, update the object's phase/rotation_count/error_count
fields according to the quadrature state machine used elsewhere in AP_Quadrature
(handling valid forward/backward transitions and incrementing error_count for
invalid transitions). Ensure the implementations use the exact function
signatures pin_ab_to_phase(bool, bool) and void update_phase_and_error_count()
so they match the header.

In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp`:
- Around line 238-240: The function set_position_offset currently writes
pos_offset_zero[instance] without validating instance; add a bounds check in
AP_RotaryEncoder::set_position_offset to ensure instance is within the valid
range (e.g., 0 <= instance <
(sizeof(pos_offset_zero)/sizeof(pos_offset_zero[0])) or compare against the
library's max instances constant) and only update pos_offset_zero when the index
is valid; on invalid index either return early or handle via an
assertion/logging to avoid out-of-bounds memory writes.
- Around line 206-226: get_counts_per_revolution and get_angular_position must
guard against zero/invalid counts-per-revolution and apply pos_offset_zero
consistently in radians: in get_counts_per_revolution ensure
_counts_per_revolution[instance] is >0 (return 0 if instance invalid or CPR==0),
and in get_angular_position first validate instance and non-zero CPR, compute
angle in radians as angle_rad = M_2_PI * state[instance].count /
_counts_per_revolution[instance] then subtract pos_offset_zero[instance] (which
should be stored/treated as radians), and finally if degrees==true convert the
resulting radians to degrees using (180.0f / M_PI); update uses of
_counts_per_revolution, state[instance].count, pos_offset_zero[instance],
ROTARY_ENCODER_MAX_INSTANCES, M_2_PI and M_PI accordingly.
- Around line 110-135: init() creates drivers based only on _type[i] causing
instances with invalid pins to be treated as enabled; change init()
(AP_RotaryEncoder::init) to validate the instance pins before instantiating
drivers (skip creating drivers[i] if pin A/B are -1 or otherwise invalid,
mirroring the check used in any_enabled()), update num_instances only when a
driver is actually created, and add an informational log when skipping due to
invalid pins; likewise update enabled() to include the same pin-validity check
(in addition to type/driver checks) so its return value matches any_enabled()
and the behavior in Log_Write().

In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.h`:
- Around line 68-70: AP_RotaryEncoder::get_delta_angle(uint8_t instance) is
declared but not defined, causing linker errors; add a concrete definition in
AP_RotaryEncoder.cpp that matches the signature (float
AP_RotaryEncoder::get_delta_angle(uint8_t instance) const) and returns the total
delta angle in radians (compute from the encoder's stored counts/last_counts and
pulses_per_revolution or delegate to existing methods like
get_delta_count/get_counts_to_radians), or if the design expects subclasses to
implement it, change the declaration in AP_RotaryEncoder.h to a pure virtual
(virtual float get_delta_angle(uint8_t instance) const = 0) so subclasses
provide implementations; ensure the chosen approach aligns with other
AP_RotaryEncoder methods and build rules.
🧹 Nitpick comments (3)
libraries/AP_Logger/LogStructure.h (1)

1416-1416: Consider keeping log message IDs stable.

Inserting LOG_ROTARYENCODER_MSG here shifts subsequent IDs. If ID stability across releases/tools matters, consider assigning an explicit value or appending at the end.

libraries/AP_RotaryEncoder/AP_Quadrature.cpp (1)

16-21: Consider removing verbose constructor logging in production.

The GCS_SEND_TEXT in the constructor is useful for debugging but may be noisy in production. Consider guarding it with a debug macro or removing it.

ArduPlane/tailsitter.cpp (1)

371-388: Add encoder configuration validation before offset initialization.

The any_enabled() method exists in AP_RotaryEncoder and validates that encoders are properly configured (type not NONE and pins not -1). Use it to guard the offset initialization to prevent setting invalid values when no encoders are configured.

The update() call on line 379 is not redundant—it only appears once in this file and the AP_RotaryEncoder::update() method includes an early return when no encoders are enabled, so it's safe to call.

♻️ Proposed guard for encoder configuration
-    if(rotary_encoder_zero && (AP_HAL::millis() > quadplane.rotary_encoder.get_init_time_ms())) {
+    if(rotary_encoder_zero && quadplane.rotary_encoder.any_enabled() && 
+       (AP_HAL::millis() > quadplane.rotary_encoder.get_init_time_ms())) {
         quadplane.rotary_encoder.set_position_offset(0, quadplane.rotary_encoder.get_angular_position(0,true));

Comment on lines +121 to +129
// Encoder parameters
AP_Int16 encoder1_pin_a;
AP_Int16 encoder1_pin_b;
AP_Int16 encoder1_cpr;
AP_Int16 encoder2_pin_a;
AP_Int16 encoder2_pin_b;
AP_Int16 encoder2_cpr;

AP_RotaryEncoder rotary_encoder;
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:

# Check how AP_RotaryEncoder handles its parameters
rg -n "AP_GROUPINFO" libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp -A2

Repository: AirboundInc/ardupilot

Length of output: 1035


🏁 Script executed:

# Also check the header file for AP_RotaryEncoder to see its structure
fd "AP_RotaryEncoder.h" libraries/

Repository: AirboundInc/ardupilot

Length of output: 110


🏁 Script executed:

# Check tailsitter.cpp to see how the encoder parameters are used
rg -n "encoder.*pin" ArduPlane/tailsitter.cpp -B2 -A2 | head -50

Repository: AirboundInc/ardupilot

Length of output: 881


🏁 Script executed:

# Check how encoder parameters are used in tailsitter.cpp
rg -n "encoder1_pin|encoder2_pin|encoder1_cpr|encoder2_cpr" ArduPlane/tailsitter.cpp -B2 -A2

Repository: AirboundInc/ardupilot

Length of output: 1163


🏁 Script executed:

# Check the AP_RotaryEncoder header to understand its structure
cat -n libraries/AP_RotaryEncoder/AP_RotaryEncoder.h | grep -A5 "_pina\|_pinb\|_counts_per_revolution" | head -40

Repository: AirboundInc/ardupilot

Length of output: 830


🏁 Script executed:

# Search for any initialization or parameter passing to rotary_encoder in tailsitter.cpp
rg -n "rotary_encoder\." ArduPlane/tailsitter.cpp -B1 -A1 | head -50

Repository: AirboundInc/ardupilot

Length of output: 1062


🏁 Script executed:

# Check if Tailsitter encoder parameters are passed to AP_RotaryEncoder during initialization
rg -n "encoder1_pin_a|encoder2_pin_a|rotary_encoder" ArduPlane/quadplane.cpp -B2 -A2 | head -80

Repository: AirboundInc/ardupilot

Length of output: 353


🏁 Script executed:

# Search for any code that writes to AP_RotaryEncoder parameters
rg -n "_pina\[|_pinb\[|_counts_per_revolution\[" libraries/AP_RotaryEncoder/ -B1 -A1

Repository: AirboundInc/ardupilot

Length of output: 3675


🏁 Script executed:

# Check tailsitter initialization function to see if encoder params are set up there
rg -n "void Tailsitter::init" ArduPlane/tailsitter.cpp -A30

Repository: AirboundInc/ardupilot

Length of output: 47


Remove unused Tailsitter encoder parameters or clarify their purpose.

The encoder pin and CPR parameters defined here (E1A, E1B, E1CPR, E2A, E2B, E2CPR) are not used by the code. Configuration flows through AP_RotaryEncoder's own parameters instead (RE_LA, RE_LB, RE_LC, RE_RA, RE_RB, RE_RC under the quadplane namespace), which are the actual pins and counts read during operation.

These Tailsitter parameters appear to be dead code that will confuse users who may configure the wrong parameter set. Either remove them or document their relationship to the AP_RotaryEncoder parameters.

🤖 Prompt for AI Agents
In `@ArduPlane/tailsitter.h` around lines 121 - 129, Remove or clarify the unused
encoder parameter members (encoder1_pin_a, encoder1_pin_b, encoder1_cpr,
encoder2_pin_a, encoder2_pin_b, encoder2_cpr) declared in tailsitter.h since
AP_RotaryEncoder (rotary_encoder) already exposes and uses its own parameters
(RE_LA, RE_LB, RE_LC, RE_RA, RE_RB, RE_RC); either delete these six AP_Int16
fields to avoid dead code and confusion, or replace them with a clear comment
above AP_RotaryEncoder explaining that encoder configuration is handled by
AP_RotaryEncoder and referencing the RE_* parameter names so maintainers/users
know which parameters to use.

Comment on lines +54 to +92
void AP_Quadrature::irq_handler(uint8_t pin, bool pin_value, uint32_t timestamp)
{
// Add interrupt debug
static uint32_t irq_count = 0;
irq_count++;


uint8_t index = 0;
if(pin == _pinA) {
index = A_value << 3 | B_value << 2 | pin_value << 1 | B_value;
A_value = pin_value;
}
else if(pin == _pinB) {
index = A_value << 3 | B_value << 2 | A_value << 1 | pin_value;
B_value = pin_value;
}
else {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "IRQ on unknown pin %d (instance %d)", pin, _state.instance);
return;
}

int8_t direction = _lookupTable[index];

// Accumulate phase changes first
irq_state.phase += direction;

// Calculate velocity using a sliding window approach
uint32_t current_time_us = timestamp;

// Get CPR from frontend and calculate angle
uint16_t cpr = _frontend.get_counts_per_revolution(_state.instance);
if (cpr > 0) {
irq_state.angle = irq_state.phase * (360.0f / cpr);
} else {
irq_state.angle = 0.0f;
}

irq_state.time = current_time_us;
}
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

Critical: Avoid GCS_SEND_TEXT inside ISR context.

Line 71 calls GCS_SEND_TEXT inside the interrupt handler, which can cause issues:

  • GCS operations may block or take non-deterministic time
  • Can cause priority inversion or deadlocks
  • May corrupt shared state if GCS is being used elsewhere

Also, the static irq_count variable (lines 57-58) is shared across all instances and serves no purpose beyond debugging.

🐛 Proposed fix
 void AP_Quadrature::irq_handler(uint8_t pin, bool pin_value, uint32_t timestamp)
 {
-    // Add interrupt debug
-    static uint32_t irq_count = 0;
-    irq_count++;
-    
-
     uint8_t index = 0;
     if(pin == _pinA) {
         index = A_value << 3 | B_value << 2 | pin_value << 1 | B_value;
         A_value = pin_value;
     }
     else if(pin == _pinB) {
         index = A_value << 3 | B_value << 2 | A_value << 1 | pin_value;
         B_value = pin_value;
     }
     else {
-        GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "IRQ on unknown pin %d (instance %d)", pin, _state.instance);
+        // Unknown pin - should not happen if pins configured correctly
         return;
     }
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_Quadrature.cpp` around lines 54 - 92, The
irq_handler function currently performs non-ISR-safe work: remove the
GCS_SEND_TEXT call from irq_handler and any other blocking calls (reference:
irq_handler, GCS_SEND_TEXT), and instead record a minimal, atomic error/event
flag or push a small event into a lock-free/ISR-safe queue (or set a volatile
status bit) that a non-ISR task will consume and call GCS_SEND_TEXT; also remove
the useless static irq_count (or convert it to an instance member if persistent
per-instance counting is required) so the ISR only updates ISR-safe state (e.g.,
irq_state.phase, irq_state.angle, irq_state.time) and enqueues/flags any
diagnostic messages for later processing.

Comment on lines +83 to +89
// Get CPR from frontend and calculate angle
uint16_t cpr = _frontend.get_counts_per_revolution(_state.instance);
if (cpr > 0) {
irq_state.angle = irq_state.phase * (360.0f / cpr);
} else {
irq_state.angle = 0.0f;
}
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

Type mismatch: irq_state.angle is uint32_t but stores a float calculation.

The angle calculation produces a float (degrees), but irq_state.angle is declared as uint32_t in the header. This causes precision loss and incorrect values for negative phases.

Either change irq_state.angle to float in the header, or store a scaled integer representation.

🐛 Proposed fix in AP_Quadrature.h
     struct IrqState {
         int32_t     phase;             
-        uint32_t    angle;             
+        float       angle;             
         uint32_t    time;
     } irq_state;
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_Quadrature.cpp` around lines 83 - 89, The code
assigns a floating-point degree value to irq_state.angle (computed from
irq_state.phase and _frontend.get_counts_per_revolution) but irq_state.angle is
declared as uint32_t, causing precision loss and wrong values for negatives;
update the irq_state.angle declaration in the header (AP_Quadrature.h) to float
(or float32) so the computed value from irq_state.phase * (360.0f / cpr) is
stored correctly, and verify any code that reads irq_state.angle handles a float
rather than an unsigned integer.

Comment on lines +24 to +28
// convert pin a and b status to phase
static uint8_t pin_ab_to_phase(bool pin_a, bool pin_b);

// update phase, rotation_count and error count using pin a and b's latest state
void update_phase_and_error_count();
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:

rg -n "pin_ab_to_phase|update_phase_and_error_count" libraries/AP_RotaryEncoder/

Repository: AirboundInc/ardupilot

Length of output: 258


🏁 Script executed:

ls -la libraries/AP_RotaryEncoder/

Repository: AirboundInc/ardupilot

Length of output: 616


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_Quadrature.cpp

Repository: AirboundInc/ardupilot

Length of output: 4215


Implement declared methods or remove declarations.

pin_ab_to_phase() and update_phase_and_error_count() are declared in the header but not implemented in AP_Quadrature.cpp. Either provide implementations or remove the declarations.

🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_Quadrature.h` around lines 24 - 28, The header
declares pin_ab_to_phase(bool pin_a, bool pin_b) and
update_phase_and_error_count() but they are missing in AP_Quadrature.cpp; either
remove those declarations from AP_Quadrature.h or add implementations in
AP_Quadrature.cpp: implement pin_ab_to_phase to map the two input booleans into
a 2-bit phase value (0..3) consistently with the rest of the class, and
implement update_phase_and_error_count to read current pin states, compute new
phase via pin_ab_to_phase, update the object's phase/rotation_count/error_count
fields according to the quadrature state machine used elsewhere in AP_Quadrature
(handling valid forward/backward transitions and incrementing error_count for
invalid transitions). Ensure the implementations use the exact function
signatures pin_ab_to_phase(bool, bool) and void update_phase_and_error_count()
so they match the header.

Comment on lines +30 to +34
struct IrqState {
int32_t phase;
uint32_t angle;
uint32_t time;
} irq_state;
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

Type consistency: angle should likely be float.

As noted in the implementation review, irq_state.angle stores a floating-point calculation result but is declared as uint32_t. This causes precision loss. Change to float for correctness.

🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_Quadrature.h` around lines 30 - 34, Change the
IrqState struct so irq_state.angle uses a floating type instead of uint32_t:
update the declaration of struct IrqState (the member named angle) from uint32_t
to float to preserve fractional results produced by the angle calculations and
avoid precision loss in code that reads/writes irq_state.angle.

Comment on lines +36 to +38
uint8_t _pinA = -1;
uint8_t _pinB = -1;
uint8_t A_value, B_value;
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

Uninitialized member variables may cause undefined behavior.

A_value and B_value are not initialized. If an interrupt fires before update_pin() is called for both pins, the ISR will read uninitialized values for the lookup table index calculation.

Also, _pinA = -1 and _pinB = -1 work due to unsigned wraparound but UINT8_MAX would be more explicit.

🐛 Proposed fix
-    uint8_t _pinA = -1;
-    uint8_t _pinB = -1;
-    uint8_t A_value, B_value;
+    uint8_t _pinA = UINT8_MAX;
+    uint8_t _pinB = UINT8_MAX;
+    uint8_t A_value = 0;
+    uint8_t B_value = 0;
📝 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
uint8_t _pinA = -1;
uint8_t _pinB = -1;
uint8_t A_value, B_value;
uint8_t _pinA = UINT8_MAX;
uint8_t _pinB = UINT8_MAX;
uint8_t A_value = 0;
uint8_t B_value = 0;
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_Quadrature.h` around lines 36 - 38, Initialize
the member variables to avoid undefined behavior: set _pinA and _pinB to
UINT8_MAX instead of -1 for clarity and initialize A_value and B_value (e.g., 0)
in the AP_Quadrature class member declarations so an interrupt won’t read
garbage before update_pin() runs; ensure the ISR and any lookup/index
computation that reads A_value/B_value will use the initialized values.

Comment on lines +110 to +135
void AP_RotaryEncoder::init(void)
{
if (num_instances != 0) {
// init called a 2nd time?
return;
}

for (uint8_t i=0; i<ROTARY_ENCODER_MAX_INSTANCES; i++) {

switch ((RotaryEncoder_Type)_type[i].get()) {

case RotaryEncoder_TYPE_QUADRATURE:
drivers[i] = new AP_Quadrature(*this, i, state[i]);
break;
case RotaryEncoder_TYPE_NONE:
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "No encoder configured for instance %d", i);
break;
}

if (drivers[i] != nullptr) {
// we loaded a driver for this instance, so it must be
// present (although it may not be healthy)
num_instances = i+1; // num_instances is a high-water-mark
}
}
}
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:

find libraries/AP_RotaryEncoder -type f \( -name "*.h" -o -name "*.cpp" \) | head -20

Repository: AirboundInc/ardupilot

Length of output: 356


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_RotaryEncoder.h | head -100

Repository: AirboundInc/ardupilot

Length of output: 4343


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp | sed -n '100,220p'

Repository: AirboundInc/ardupilot

Length of output: 4314


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_Quadrature.h

Repository: AirboundInc/ardupilot

Length of output: 1686


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_Quadrature.cpp | head -150

Repository: AirboundInc/ardupilot

Length of output: 4215


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_RotaryEncoder_Backend.h

Repository: AirboundInc/ardupilot

Length of output: 2006


🏁 Script executed:

cat -n libraries/AP_RotaryEncoder/AP_RotaryEncoder_Backend.cpp

Repository: AirboundInc/ardupilot

Length of output: 2455


🏁 Script executed:

rg -n "AP_Param::GroupInfo.*var_info" -A 100 libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp | head -150

Repository: AirboundInc/ardupilot

Length of output: 4012


Inconsistent pin validation between enabled() and any_enabled() creates confusion about instance state.

The init() method creates drivers based solely on type, while enabled() returns true for instances with invalid pins (-1). Meanwhile, any_enabled() explicitly checks pin validity. This inconsistency causes Log_Write() to potentially log data for non-functional instances, and enabled() to misrepresent instance state.

The core issue: if a user sets encoder type without configuring pins, the instance reports as enabled even though updates are skipped. Add pin validation to init() before driver instantiation and to enabled() for consistency with any_enabled().

Suggested fix
         case RotaryEncoder_TYPE_QUADRATURE:
+            if (_pina[i] < 0 || _pinb[i] < 0) {
+                GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RotaryEncoder %u pins not configured", i);
+                break;
+            }
             drivers[i] = new AP_Quadrature(*this, i, state[i]);
             break;
 bool AP_RotaryEncoder::enabled(uint8_t instance) const
 {
     if (instance >= num_instances) {
         return false;
     }
     if (_type[instance] == RotaryEncoder_TYPE_NONE) {
         return false;
     }
+    if (_pina[instance] < 0 || _pinb[instance] < 0) {
+        return false;
+    }
     return true;
 }
 bool AP_RotaryEncoder::any_enabled(void) const
 {
     for (uint8_t i = 0; i < ROTARY_ENCODER_MAX_INSTANCES; i++) {
-        if (_type[i] != RotaryEncoder_TYPE_NONE && 
-            _pina[i] != -1 && 
-            _pinb[i] != -1) {
+        if (enabled(i)) {
             return true;
         }
     }
     return false;
 }
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp` around lines 110 - 135,
init() creates drivers based only on _type[i] causing instances with invalid
pins to be treated as enabled; change init() (AP_RotaryEncoder::init) to
validate the instance pins before instantiating drivers (skip creating
drivers[i] if pin A/B are -1 or otherwise invalid, mirroring the check used in
any_enabled()), update num_instances only when a driver is actually created, and
add an informational log when skipping due to invalid pins; likewise update
enabled() to include the same pin-validity check (in addition to type/driver
checks) so its return value matches any_enabled() and the behavior in
Log_Write().

Comment on lines +206 to +226
// get the counts per revolution of the encoder
uint16_t AP_RotaryEncoder::get_counts_per_revolution(uint8_t instance) const
{
// for invalid instances return zero vector
if (instance >= ROTARY_ENCODER_MAX_INSTANCES) {
return 0;
}
return (uint16_t)_counts_per_revolution[instance];
}

// get the angular position in degrees
float AP_RotaryEncoder::get_angular_position(uint8_t instance, bool degrees) const
{
// for invalid instances return zero
if (instance >= ROTARY_ENCODER_MAX_INSTANCES) {
return 0.0f;
}

float position = M_2_PI * state[instance].count / _counts_per_revolution[instance];
return degrees ? position * (180.0f / M_PI) - pos_offset_zero[instance] : position - pos_offset_zero[instance] * M_2_PI / _counts_per_revolution[instance];
}
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

Guard against invalid CPR and fix offset unit mismatch.

_counts_per_revolution can be zero/negative (no range clamp), which yields divide-by-zero/NaN. Also, the offset is applied in degrees branch differently than radians branch, so units are inconsistent. Please standardize on one internal unit (radians recommended) and apply conversions consistently.

🧭 Suggested fix (radians as internal unit)
@@ float AP_RotaryEncoder::get_angular_position(uint8_t instance, bool degrees) const
-    float position = M_2_PI * state[instance].count / _counts_per_revolution[instance];
-    return degrees ? position * (180.0f / M_PI) - pos_offset_zero[instance] : position - pos_offset_zero[instance] * M_2_PI / _counts_per_revolution[instance];
+    const int16_t cpr = _counts_per_revolution[instance].get();
+    if (cpr <= 0) {
+        return 0.0f;
+    }
+
+    const float position_rad = M_2_PI * state[instance].count / cpr;
+    const float position_rad_offset = position_rad - pos_offset_zero[instance];
+    return degrees ? position_rad_offset * (180.0f / M_PI) : position_rad_offset;
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp` around lines 206 - 226,
get_counts_per_revolution and get_angular_position must guard against
zero/invalid counts-per-revolution and apply pos_offset_zero consistently in
radians: in get_counts_per_revolution ensure _counts_per_revolution[instance] is
>0 (return 0 if instance invalid or CPR==0), and in get_angular_position first
validate instance and non-zero CPR, compute angle in radians as angle_rad =
M_2_PI * state[instance].count / _counts_per_revolution[instance] then subtract
pos_offset_zero[instance] (which should be stored/treated as radians), and
finally if degrees==true convert the resulting radians to degrees using (180.0f
/ M_PI); update uses of _counts_per_revolution, state[instance].count,
pos_offset_zero[instance], ROTARY_ENCODER_MAX_INSTANCES, M_2_PI and M_PI
accordingly.

Comment on lines +238 to +240
void AP_RotaryEncoder::set_position_offset(uint8_t instance, float position) {
pos_offset_zero[instance] = position;
}
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

Add bounds check to avoid OOB writes in set_position_offset.

instance is not validated, so a bad index can overwrite memory.

🛡️ Suggested fix
 void AP_RotaryEncoder::set_position_offset(uint8_t instance, float position) {
-    pos_offset_zero[instance] = position;
+    if (instance >= ROTARY_ENCODER_MAX_INSTANCES) {
+        return;
+    }
+    pos_offset_zero[instance] = position;
 }
📝 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
void AP_RotaryEncoder::set_position_offset(uint8_t instance, float position) {
pos_offset_zero[instance] = position;
}
void AP_RotaryEncoder::set_position_offset(uint8_t instance, float position) {
if (instance >= ROTARY_ENCODER_MAX_INSTANCES) {
return;
}
pos_offset_zero[instance] = position;
}
🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp` around lines 238 - 240, The
function set_position_offset currently writes pos_offset_zero[instance] without
validating instance; add a bounds check in AP_RotaryEncoder::set_position_offset
to ensure instance is within the valid range (e.g., 0 <= instance <
(sizeof(pos_offset_zero)/sizeof(pos_offset_zero[0])) or compare against the
library's max instances constant) and only update pos_offset_zero when the index
is valid; on invalid index either return early or handle via an
assertion/logging to avoid out-of-bounds memory writes.

Comment on lines +68 to +70
// get total delta angle (in radians) measured by the rotary encoder
float get_delta_angle(uint8_t instance) const;

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

🧩 Analysis chain

🏁 Script executed:

#!/bin/bash
# Search for all occurrences of get_delta_angle in headers and implementation files
rg -n 'get_delta_angle' --type-add 'headers:include,*.h' --type-add 'impls:*.cpp,*.c' -t headers -t impls -C 2

Repository: AirboundInc/ardupilot

Length of output: 213


🏁 Script executed:

#!/bin/bash
# Search specifically for AP_RotaryEncoder::get_delta_angle implementation in cpp files
rg -n 'AP_RotaryEncoder::get_delta_angle' -t cpp -A 10

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# First, locate all AP_RotaryEncoder files
find . -type f -name '*AP_RotaryEncoder*' 2>/dev/null

Repository: AirboundInc/ardupilot

Length of output: 276


🏁 Script executed:

#!/bin/bash
# Basic search for get_delta_angle without type filters
rg 'get_delta_angle' -C 3

Repository: AirboundInc/ardupilot

Length of output: 9851


🏁 Script executed:

#!/bin/bash
# Check AP_RotaryEncoder.cpp for the implementation
wc -l ./libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp
head -150 ./libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp

Repository: AirboundInc/ardupilot

Length of output: 5415


🏁 Script executed:

#!/bin/bash
# Search for the implementation in AP_RotaryEncoder.cpp
grep -n 'get_delta_angle' ./libraries/AP_RotaryEncoder/AP_RotaryEncoder.cpp -A 5

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# Check AP_RotaryEncoder_Backend.cpp for implementation
grep -n 'get_delta_angle' ./libraries/AP_RotaryEncoder/AP_RotaryEncoder_Backend.cpp -A 5

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# Read the header file to see the declaration
cat -n ./libraries/AP_RotaryEncoder/AP_RotaryEncoder.h | head -80

Repository: AirboundInc/ardupilot

Length of output: 3527


🏁 Script executed:

#!/bin/bash
# Read full header to check for inline or template implementations
cat ./libraries/AP_RotaryEncoder/AP_RotaryEncoder.h

Repository: AirboundInc/ardupilot

Length of output: 3708


🏁 Script executed:

#!/bin/bash
# Search all cpp files in the directory for get_delta_angle
find ./libraries/AP_RotaryEncoder -name '*.cpp' -exec grep -l 'get_delta_angle' {} \;

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# Search for calls to get_delta_angle on rotary encoder instances
rg 'rotaryencoder.*get_delta_angle|rotary_encoder.*get_delta_angle' -C 2

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# Check git history for AP_RotaryEncoder.h to see when this was added
cd ./libraries/AP_RotaryEncoder && git log --oneline -20 AP_RotaryEncoder.h 2>/dev/null || echo "Git history not available"

Repository: AirboundInc/ardupilot

Length of output: 120


🏁 Script executed:

#!/bin/bash
# Search entire codebase for AP_RotaryEncoder::get_delta_angle definition (look for opening brace)
rg 'AP_RotaryEncoder::get_delta_angle' -A 3

Repository: AirboundInc/ardupilot

Length of output: 47


🏁 Script executed:

#!/bin/bash
# Also check if there's any implementation at all, including in test files or other locations
find . -name '*.cpp' -o -name '*.h' | xargs grep -l 'get_delta_angle' | xargs grep -A 5 'get_delta_angle.*{' | grep -A 5 'float\|return'

Repository: AirboundInc/ardupilot

Length of output: 1452


Implement AP_RotaryEncoder::get_delta_angle() to resolve linker error.

The method is declared at line 69 but has no implementation anywhere in the codebase. This will cause a linker error when the method is called. Add the implementation in AP_RotaryEncoder.cpp or mark it as pure virtual if it should be implemented by subclasses.

🤖 Prompt for AI Agents
In `@libraries/AP_RotaryEncoder/AP_RotaryEncoder.h` around lines 68 - 70,
AP_RotaryEncoder::get_delta_angle(uint8_t instance) is declared but not defined,
causing linker errors; add a concrete definition in AP_RotaryEncoder.cpp that
matches the signature (float AP_RotaryEncoder::get_delta_angle(uint8_t instance)
const) and returns the total delta angle in radians (compute from the encoder's
stored counts/last_counts and pulses_per_revolution or delegate to existing
methods like get_delta_count/get_counts_to_radians), or if the design expects
subclasses to implement it, change the declaration in AP_RotaryEncoder.h to a
pure virtual (virtual float get_delta_angle(uint8_t instance) const = 0) so
subclasses provide implementations; ensure the chosen approach aligns with other
AP_RotaryEncoder methods and build rules.

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.

2 participants