.pr_agent_auto_best_practices - iNavFlight/inav GitHub Wiki
Pattern 1: Validate external inputs and message payloads (sizes, ranges, frames, NaN) before reading/using them, and return a deterministic error or fallback value when invalid. Use explicit sentinel values for “no data yet” states to avoid treating startup/failed reads as valid measurements.
Example code before:
// payload handler
uint8_t id = buf[0];
uint16_t pos = readU16(&buf[1]); // assumes buf has >= 3 bytes
// telemetry command
wp.heading = msg.param4; // assumes valid degrees
// sensor state
rangefinder.measurementCm = 0; // 0 looks like a real reading
Example code after:
// payload handler
if (len < 3) return ERR_INVALID_LEN;
uint8_t id = buf[0];
uint16_t pos = readU16(&buf[1]);
// telemetry command
if (!isnan(msg.param4) && msg.param4 >= 0.0f && msg.param4 < 360.0f) {
wp.heading = msg.param4;
} else {
wp.heading = HEADING_NO_CHANGE; // sentinel
}
// sensor state
rangefinder.measurementCm = RANGEFINDER_NO_NEW_DATA;
Relevant past accepted suggestions:
Suggestion 1:
Add payload size validation check
Add a payload size check in the MSP_OSD_CUSTOM_POSITION handler to ensure the incoming data is at least 3 bytes before reading from the buffer.
src/main/fc/fc_msp.c [2718-2731]
case MSP_OSD_CUSTOM_POSITION: {
+ if (dataSize < 3) {
+ return MSP_RESULT_ERROR;
+ }
uint8_t item;
sbufReadU8Safe(&item, src);
if (item < OSD_ITEM_COUNT){ // item == addr
osdEraseCustomItem(item);
osdLayoutsConfigMutable()->item_pos[0][item] = sbufReadU16(src) | (1 << 13);
osdDrawCustomItem(item);
}
else{
return MSP_RESULT_ERROR;
}
break;
}Suggestion 2:
Handle yaw from MAVLink command
Handle the yaw parameter (param4) from the MAV_CMD_DO_REPOSITION command instead of ignoring it, by assigning it to wp.p1 to control the vehicle's heading.
src/main/telemetry/mavlink.c [1150-1153]
-wp.p1 = wp.p2 = wp.p3 = 0;
+if (!isnan(msg.param4) && msg.param4 >= 0.0f && msg.param4 < 360.0f) {
+ wp.p1 = msg.param4;
+} else {
+ wp.p1 = -1; // Use -1 to indicate no heading change
+}
+wp.p2 = wp.p3 = 0;
wp.flag = 0;
setWaypoint(255, ℘);Suggestion 3:
Support additional MAVLink coordinate frames
Add support for MAV_FRAME_GLOBAL_RELATIVE_ALT and MAV_FRAME_GLOBAL_TERRAIN_ALT coordinate frames to improve compatibility with various Ground Control Stations.
src/main/telemetry/mavlink.c [1131-1142]
-if (msg.frame != MAV_FRAME_GLOBAL) {
+if (msg.frame != MAV_FRAME_GLOBAL && msg.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT && msg.frame != MAV_FRAME_GLOBAL_TERRAIN_ALT) {
mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
msg.command,
MAV_RESULT_UNSUPPORTED,
0, // progress
0, // result_param2
mavRecvMsg.sysid,
mavRecvMsg.compid);
mavlinkSendMessage();
return true;
}Suggestion 4:
Prevent division-by-zero in TPA calculation
Add a check to prevent division-by-zero when referenceAirspeed is zero in the tpaThrottle calculation, falling back to the standard throttle value if necessary.
src/main/flight/pid.c [501-502]
const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s
-tpaThrottle = currentControlRateProfile->throttle.pa_breakpoint + (uint16_t)((airspeed - referenceAirspeed) / referenceAirspeed * (currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue()));
+if (referenceAirspeed > 0) {
+ tpaThrottle = currentControlRateProfile->throttle.pa_breakpoint + (uint16_t)((airspeed - referenceAirspeed) / referenceAirspeed * (currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue()));
+} else {
+ // Fallback to regular throttle if reference airspeed is not configured
+ tpaThrottle = rcCommand[THROTTLE];
+}Suggestion 5:
Suggestion 6:
Pattern 2: Keep units and normalization consistent within math-heavy code: perform computations in a single base unit, normalize once at the end, and avoid premature casts that lose precision. Use clear sign conventions and explicit invalid sentinels to keep operand semantics stable across features.
Example code before:
int16_t yawDeg = (int16_t)yawCd / 100; // early conversion
int16_t rel = (int16_t)(windCd - yawDeg); // mixes units
rel = -rel; // unclear convention
return rel;
Example code after:
int32_t yawCd = DECIDEGREES_TO_CENTIDEGREES(attitudeYawDd);
int32_t relCd = windHeadingCd - yawCd; // centidegrees only
while (relCd <= -18000) relCd += 36000;
while (relCd > 18000) relCd -= 36000;
return CENTIDEGREES_TO_DEGREES(relCd); // convert once
Relevant past accepted suggestions:
Suggestion 1:
Harmonize operand semantics and docs
Mirror the sign and invalid-return conventions with the new relative wind field in docs and keep operand meanings consistent; update docs and ensure both operands follow the same invalid sentinel and frame definitions.
src/main/programming/logic_condition.c [763-785]
-case LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION: // deg
+case LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION: // deg, 0..359, -1 invalid
#ifdef USE_WIND_ESTIMATOR
{
if (isEstimatedWindSpeedValid()) {
- uint16_t windAngle;
- getEstimatedHorizontalWindSpeed(&windAngle);
- int32_t windHeading = windAngle + 18000; // Correct heading to display correctly.
-
- windHeading = (CENTIDEGREES_TO_DEGREES((int)windHeading));
- while (windHeading < 0) {
- windHeading += 360;
- }
- while (windHeading >= 360) {
- windHeading -= 360;
- }
- return windHeading;
- } else
+ uint16_t windAngleCd;
+ getEstimatedHorizontalWindSpeed(&windAngleCd);
+ // Convert wind vector angle (towards) to heading-from (meteorological) in degrees [0,360)
+ int32_t headingDeg = CENTIDEGREES_TO_DEGREES((int)(windAngleCd + 18000));
+ while (headingDeg < 0) headingDeg += 360;
+ while (headingDeg >= 360) headingDeg -= 360;
+ return headingDeg;
+ } else {
return -1;
+ }
}
#else
- return -1;
+ return -1;
#endif
- break;
+ break;Suggestion 2:
Normalize angles in one unit
Keep all math in centidegrees until final conversion and normalize once; avoid redundant casts and flips that can introduce off-by-one errors.
src/main/programming/logic_condition.c [787-816]
-case LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET: // deg
+case LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET: // deg, signed [-180,180], 0 = headwind, left negative
#ifdef USE_WIND_ESTIMATOR
{
if (isEstimatedWindSpeedValid()) {
- uint16_t windAngle;
- getEstimatedHorizontalWindSpeed(&windAngle);
- gvSet(3, DECIDEGREES_TO_DEGREES(attitude.values.yaw));
- int32_t relativeWindHeading = windAngle + 18000 - DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw);
-
- relativeWindHeading = (CENTIDEGREES_TO_DEGREES((int)relativeWindHeading));
- while (relativeWindHeading < 0) {
- relativeWindHeading += 360;
- }
- while (relativeWindHeading >= 360) {
- relativeWindHeading -= 360;
- }
-
- relativeWindHeading = -relativeWindHeading;
- if (relativeWindHeading <= -180) {
- relativeWindHeading = 180 + (relativeWindHeading + 180);
- }
-
- return relativeWindHeading;
- } else
+ uint16_t windAngleCd;
+ getEstimatedHorizontalWindSpeed(&windAngleCd); // [0,36000)
+ // Convert wind vector angle (towards) to heading-from
+ int32_t windHeadingCd = (int32_t)windAngleCd + 18000; // centidegrees
+ // Normalize to [0,36000)
+ while (windHeadingCd < 0) windHeadingCd += 36000;
+ while (windHeadingCd >= 36000) windHeadingCd -= 36000;
+ // Aircraft yaw is in decidegrees; convert to centidegrees
+ int32_t yawCd = DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw);
+ // Relative offset: wind heading relative to aircraft nose (right positive)
+ int32_t relCd = windHeadingCd - yawCd; // centidegrees
+ // Normalize to (-18000, 18000]
+ while (relCd <= -18000) relCd += 36000;
+ while (relCd > 18000) relCd -= 36000;
+ // Convert to degrees with sign convention: left negative
+ int32_t relDeg = CENTIDEGREES_TO_DEGREES(relCd);
+ return relDeg;
+ } else {
return 0;
+ }
}
#else
- return 0;
+ return 0;
#endif
- break;
+ break;Suggestion 3:
Avoid premature type casting to float
In osdGet3DSpeed, declare vert_speed and hor_speed as float to prevent loss of precision from premature casting before the Pythagorean calculation.
src/main/io/osd_common.c [202-207]
int16_t osdGet3DSpeed(void)
{
- int16_t vert_speed = getEstimatedActualVelocity(Z);
- int16_t hor_speed = gpsSol.groundSpeed;
+ float vert_speed = getEstimatedActualVelocity(Z);
+ float hor_speed = gpsSol.groundSpeed;
return (int16_t)calc_length_pythagorean_2D(hor_speed, vert_speed);
}Suggestion 4:
Pattern 3: Ensure cross-module behavior and documentation stay synchronized: centralize or mirror priority/meaning rules (e.g., flight mode strings, operand frames) and update docs/links when code moves. Avoid divergent implementations of the same concept across telemetry/OSD/docs.
Example code before:
// telemetry.c
if (modeFailsafe()) s = "!FS!";
else if (modeGeozone()) s = "GEO";
else if (modeManual()) s = "MANU";
// osd.c (different order)
if (modeFailsafe()) s = "!FS!";
else if (modeManual()) s = "MANU";
else if (modeGeozone()) s = "GEO";
Example code after:
// shared helper used by both telemetry + OSD
const char *flightModeLabel(void) {
if (modeFailsafe()) return "!FS!";
if (modeManual()) return "MANU";
if (modeGeozone()) return "GEO";
return "----";
}
Relevant past accepted suggestions:
Suggestion 1:
Harmonize operand semantics and docs
Mirror the sign and invalid-return conventions with the new relative wind field in docs and keep operand meanings consistent; update docs and ensure both operands follow the same invalid sentinel and frame definitions.
src/main/programming/logic_condition.c [763-785]
-case LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION: // deg
+case LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION: // deg, 0..359, -1 invalid
#ifdef USE_WIND_ESTIMATOR
{
if (isEstimatedWindSpeedValid()) {
- uint16_t windAngle;
- getEstimatedHorizontalWindSpeed(&windAngle);
- int32_t windHeading = windAngle + 18000; // Correct heading to display correctly.
-
- windHeading = (CENTIDEGREES_TO_DEGREES((int)windHeading));
- while (windHeading < 0) {
- windHeading += 360;
- }
- while (windHeading >= 360) {
- windHeading -= 360;
- }
- return windHeading;
- } else
+ uint16_t windAngleCd;
+ getEstimatedHorizontalWindSpeed(&windAngleCd);
+ // Convert wind vector angle (towards) to heading-from (meteorological) in degrees [0,360)
+ int32_t headingDeg = CENTIDEGREES_TO_DEGREES((int)(windAngleCd + 18000));
+ while (headingDeg < 0) headingDeg += 360;
+ while (headingDeg >= 360) headingDeg -= 360;
+ return headingDeg;
+ } else {
return -1;
+ }
}
#else
- return -1;
+ return -1;
#endif
- break;
+ break;Suggestion 2:
Align flight mode priority logic
Align the flight mode priority logic in crsf.c with osd.c. The current implementation has a different priority for MANUAL_MODE and GEOZONE between the two files, which should be synchronized.
src/main/telemetry/crsf.c [356-368]
#ifdef USE_FW_AUTOLAND
if (FLIGHT_MODE(NAV_FW_AUTOLAND)) {
flightMode = "LAND";
} else
#endif
if (FLIGHT_MODE(FAILSAFE_MODE)) {
flightMode = "!FS!";
+ } else if (FLIGHT_MODE(MANUAL_MODE)) {
+ flightMode = "MANU";
#ifdef USE_GEOZONE
} else if (FLIGHT_MODE(NAV_SEND_TO) && !FLIGHT_MODE(NAV_WP_MODE)) {
flightMode = "GEO";
-#endif
- } else if (FLIGHT_MODE(MANUAL_MODE)) {
- flightMode = "MANU";
+#endifSuggestion 3:
Fix broken enum links in tables
Description: Sets navigation position hold and general manual/auto flight parameters.
Request Payload:
-| Field | C Type | Size (Bytes) | Units | Description |
+|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| userControlMode | uint8_t | 1 | ENUM_NAME | Sets navConfigMutable()->general.flags.user_control_mode | | maxAutoSpeed|uint16_t| 2 | cm/s | SetsnavConfigMutable()->general.max_auto_speed |
@@ -442,7 +441,7 @@
| maxManualSpeed | uint16_t | 2 | cm/s | Sets navConfigMutable()->general.max_manual_speed | | maxManualClimbRate|uint16_t| 2 | cm/s | Setsfw.max_manual_climb_rateormc.max_manual_climb_rate |
| mcMaxBankAngle | uint8_t | 1 | degrees | Sets navConfigMutable()->mc.max_bank_angle | -| mcAltHoldThrottleType|uint8_t| 1 | [navMcAltHoldThrottle_e](https://github.com/iNavFlight/inav/wiki/inav_enums_ref.md#enum-navmcaltholdthrottle_e) | EnumnavMcAltHoldThrottle_eSets 'navConfigMutable()->mc.althold_throttle_type' | +|mcAltHoldThrottleType|uint8_t| 1 | [navMcAltHoldThrottle_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-navmcaltholdthrottle_e) | EnumnavMcAltHoldThrottle_eSets 'navConfigMutable()->mc.althold_throttle_type' | |mcHoverThrottle|uint16_t| 2 | PWM | SetscurrentBatteryProfileMutable->nav.mc.hover_throttle |
**Fix the broken link for navMcAltHoldThrottle_e in the MSP_NAV_POSHOLD table to point to the correct enum documentation.**
[docs/development/msp/msp_ref.md [430]](https://github.com/iNavFlight/inav/pull/11088/files#diff-bd5d16f1d7479f638d11be77b5b1f15c8adeca02e5c0abc7426f046ece93fd95R430-R430)
```diff
-| `mcAltHoldThrottleType` | `uint8_t` | 1 | [navMcAltHoldThrottle_e](https://github.com/iNavFlight/inav/wiki/inav_enums_ref.md#enum-navmcaltholdthrottle_e) | Enum `navMcAltHoldThrottle_e` Sets 'navConfigMutable()->mc.althold_throttle_type' |
+| `mcAltHoldThrottleType` | `uint8_t` | 1 | [navMcAltHoldThrottle_e](https://github.com/xznhj8129/msp_documentation/blob/master/docs/inav_enums_ref.md#navmcaltholdthrottle_e) | Enum `navMcAltHoldThrottle_e` Sets 'navConfigMutable()->mc.althold_throttle_type' |
Suggestion 4:
Pattern 4: Keep the repository clean of generated/environment-specific artifacts and avoid build steps that modify tracked source files; instead, write outputs to the build directory or gate updates behind an explicit flag. Add generated directories/files to .gitignore when appropriate.
Example code before:
# CMakeLists.txt
add_custom_command(TARGET fw POST_BUILD
COMMAND ${PYTHON} tools/update_db.py cmake/pg_struct_sizes.db
)
# (and generated CMakeFiles/* committed to git)
Example code after:
# CMakeLists.txt
add_custom_command(TARGET fw POST_BUILD
COMMAND ${PYTHON} tools/update_db.py
--input ${CMAKE_SOURCE_DIR}/cmake/pg_struct_sizes.db
--output ${CMAKE_BINARY_DIR}/pg_struct_sizes.db.updated
)
message(STATUS "To apply: copy pg_struct_sizes.db.updated into cmake/pg_struct_sizes.db")
# .gitignore
CMakeFiles/
CMakeCache.txt
Relevant past accepted suggestions:
Suggestion 1:
Remove generated build file from repository
Remove the generated CMake build file from the repository. It contains user-specific absolute paths that will cause build failures for other developers and should be added to .gitignore.
-# Consider dependencies only in project.
-set(CMAKE_DEPENDS_IN_PROJECT_ONLY OFF)
+# This file should be removed from the repository.
-# The set of languages for which implicit dependencies are needed:
-set(CMAKE_DEPENDS_LANGUAGES
- "ASM"
- )
-# The set of files for implicit dependencies of each language:
-set(CMAKE_DEPENDS_CHECK_ASM
- "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/lib/main/CMSIS/DSP/Source/TransformFunctions/arm_bitreversal2.S" "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/src/src/main/target/AXISFLYINGF7PRO/CMakeFiles/AXISFLYINGF7PRO_for_bl.elf.dir/__/__/__/__/lib/main/CMSIS/DSP/Source/TransformFunctions/arm_bitreversal2.S.obj"
- "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/src/main/startup/startup_stm32f722xx.s" "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/src/src/main/target/AXISFLYINGF7PRO/CMakeFiles/AXISFLYINGF7PRO_for_bl.elf.dir/__/__/startup/startup_stm32f722xx.s.obj"
- )
-set(CMAKE_ASM_COMPILER_ID "GNU")
-
-# Preprocessor definitions for this target.
-set(CMAKE_TARGET_DEFINITIONS_ASM
-...
-
-# The include file search paths:
-set(CMAKE_ASM_TARGET_INCLUDE_PATH
- "main/target/AXISFLYINGF7PRO"
- "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Inc"
- "/Users/ahmed/Desktop/Projects/INAV-RPiOSD/inav/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include"
-...
-Suggestion 2:
Remove generated file from version control
Remove the generated Makefile.cmake file from version control. This file is environment-specific and should be ignored by adding the CMakeFiles directory to .gitignore.
src/CMakeFiles/Makefile.cmake [1-9]
-# CMAKE generated file: DO NOT EDIT!
-# Generated by "Unix Makefiles" Generator, CMake Version 4.1
+# This file should be removed from the pull request and repository.
-# The generator used is:
-set(CMAKE_DEPENDS_GENERATOR "Unix Makefiles")
-
-# The top level Makefile was generated from the following files:
-set(CMAKE_MAKEFILE_DEPENDS
- "CMakeCache.txt"
-...
-Suggestion 3:
Pattern 5: In embedded/IO paths, make failure modes non-blocking and state-safe: add timeouts to polling loops, ensure periodic retriggers happen even on early returns, and avoid large stack allocations by using static buffers when sizes can grow. Prefer safe deletion/cleanup commands in scripts to avoid catastrophic removal.
Example code before:
void task(void) {
uint8_t tmp[BIG_SIZE]; // large stack buffer
while (!sdReady()) { } // can hang forever
if (!readOk()) return; // exits before retrigger
triggerNextMeasurement();
}
rm -rf */ # dangerous cleanup
Example code after:
static uint8_t tmp[BIG_SIZE]; // avoid stack blowups
for (int i = 0; i < 1000 && !sdReady(); i++) {
delay(1);
}
if (!sdReady()) return ERR_TIMEOUT;
triggerNextMeasurement(); // scheduled before any early return
if (!readOk()) return ERR_IO;
find . -type d -empty -delete # safer cleanup
Relevant past accepted suggestions:
Suggestion 1:
Use static allocation for array
The array servoMixerSwitchHelper is allocated on the stack with a size that could be large (MAX_SERVO_RULES/2). This could cause stack overflow in embedded systems with limited stack space. Consider using static allocation or dynamic allocation instead.
src/main/flight/servos.c [211-227]
//move the rate filter to new servo rules
int maxMoveFilters = MAX_SERVO_RULES/2;
int movefilterCount = 0;
-servoMixerSwitch_t servoMixerSwitchHelper[maxMoveFilters]; // helper to keep track of servoSpeedLimitFilter of servo rules
+static servoMixerSwitch_t servoMixerSwitchHelper[MAX_SERVO_RULES/2]; // helper to keep track of servoSpeedLimitFilter of servo rules
memset(servoMixerSwitchHelper, 0, sizeof(servoMixerSwitchHelper));
for (int i = 0; i < servoRuleCount; i++) {
if(currentServoMixer[i].inputSource == INPUT_MIXER_SWITCH_HELPER || movefilterCount >= maxMoveFilters) {
break;
}
if(currentServoMixer[i].speed != 0 && servoSpeedLimitFilter[i].state !=0) {
servoMixerSwitchHelper[movefilterCount].targetChannel = currentServoMixer[i].targetChannel;
servoMixerSwitchHelper[movefilterCount].speed = currentServoMixer[i].speed;
servoMixerSwitchHelper[movefilterCount].rate = currentServoMixer[i].rate;
servoMixerSwitchHelper[movefilterCount].speedLimitFilterState = servoSpeedLimitFilter[i].state;
movefilterCount++;
}
}Suggestion 2:
Suggestion 3:
Suggestion 4:
[Auto-generated best practices - 2026-02-09]