37 #include "rosflight.h" 88 bool update_integrators =
122 fake_state.
roll = 0.0f;
123 fake_state.
pitch = 0.0f;
124 fake_state.
yaw = 0.0f;
143 "Cannot perform equilibrium offset calibration while armed");
179 bool update_integrators)
184 float dt = 1e-6 * dt_us;
218 differentiator_(0.0
f),
252 return run(dt, x, x_c, update_integrator, xdot);
258 float error = x_c - x;
261 float p_term = error *
kp_;
272 if ((
ki_ > 0.0
f) && update_integrator)
281 float u = p_term - d_term + i_term;
286 if (u != u_sat &&
fabs(i_term) >
fabs(u - p_term + d_term) &&
ki_ > 0.0f)
Controller(ROSflight &rf)
static volatile bool error
void log(CommLinkInterface::LogSeverity severity, const char *fmt,...)
const control_t & combined_control() const
const control_t & rc_control() const
turbomath::Vector run_pid_loops(uint32_t dt, const Estimator::State &state, const control_t &command, bool update_integrators)
bool set_param_float(uint16_t id, float value)
Sets the value of a floating point parameter by ID and calls the parameter callback.
CommManager comm_manager_
void init(float kp, float ki, float kd, float max, float min, float tau)
float get_param_float(uint16_t id) const
Get the value of a floating point parameter by id.
const State & state() const
float run(float dt, float x, float x_c, bool update_integrator)
void param_change_callback(uint16_t param_id) override
const State & state() const
void set_error(uint16_t error)
turbomath::Quaternion attitude
turbomath::Vector angular_velocity
StateManager state_manager_
void calculate_equilbrium_torque_from_rc()
CommandManager command_manager_