From 5d151c54a4bafb3e176fdc96e4de321329ea0ff4 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:10:11 -0800 Subject: [PATCH] flight_mode_manager: call direct parent instead of grandparent FlightTaskManualAcceleration and FlightTaskOrbit both inherit from FlightTaskManualAltitudeSmoothVel but were calling FlightTask and FlightTaskManualAltitude respectively, skipping the intermediate parent's overrides (smoothing velocity init, parameter chain). Fix the DEFINE_PARAMETERS_CUSTOM_PARENT macro argument and the activate() call to use FlightTaskManualAltitudeSmoothVel. Fixes bugprone-parent-virtual-call clang-tidy diagnostic. Signed-off-by: Ramon Roche --- .../tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp | 2 +- src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp index 56fefcc792..2ce9a7c44f 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp @@ -52,7 +52,7 @@ protected: StickAccelerationXY _stick_acceleration_xy{this}; WeatherVane _weathervane{this}; /**< weathervane library, used to implement a yaw control law that turns the vehicle nose into the wind */ - DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask, + DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTaskManualAltitudeSmoothVel, (ParamFloat) _param_mpc_vel_manual, (ParamFloat) _param_mpc_acc_hor ) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index d8b68b0db3..55c6b64273 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -173,7 +173,7 @@ void FlightTaskOrbit::_sanitizeParams(float &radius, float &velocity) const bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) { - bool ret = FlightTaskManualAltitude::activate(last_setpoint); + bool ret = FlightTaskManualAltitudeSmoothVel::activate(last_setpoint); _currently_orbiting = false; _orbit_radius = _radius_min; _orbit_velocity = 1.f;