Skip to content

Commit

Permalink
AC_AttitudeControl: raise a config error if rate_controller_run_dt() …
Browse files Browse the repository at this point in the history
…is called by accident
  • Loading branch information
andyp1per committed Sep 23, 2024
1 parent c476d20 commit 54deea9
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AC_AttitudeControl/AC_AttitudeControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <AC_PID/AC_PID.h>
#include <AC_PID/AC_P.h>
#include <AP_Vehicle/AP_MultiCopter.h>
#include <AP_BoardConfig/AP_BoardConfig.h>

#define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw

Expand Down Expand Up @@ -244,7 +245,7 @@ class AC_AttitudeControl {
virtual void rate_controller_target_reset() {}

// optional variant to allow running with different dt
virtual void rate_controller_run_dt(float dt, const Vector3f& gyro) {}
virtual void rate_controller_run_dt(float dt, const Vector3f& gyro) { AP_BoardConfig::config_error("rate_controller_run_dt() must be defined"); };

// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
void euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads);
Expand Down

0 comments on commit 54deea9

Please sign in to comment.