37 #include "rosflight.h" 200 fake_state.
roll = 0.0f;
201 fake_state.
pitch = 0.0f;
202 fake_state.
yaw = 0.0f;
231 bool update_integrators)
236 float dt = 1e-6*dt_us;
270 differentiator_(0.0
f),
303 return run(dt, x, x_c, update_integrator, xdot);
309 float error = x_c - x;
312 float p_term = error *
kp_;
323 if ((
ki_ > 0.0
f) && update_integrator)
332 float u = p_term - d_term + i_term;
337 if (u != u_sat &&
fabs(i_term) >
fabs(u - p_term + d_term) &&
ki_ > 0.0f)
void param_change_callback(uint16_t param_id)
Controller(ROSflight &rf)
static volatile bool error
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 add_callback(std::function< void(int)> callback, uint16_t param_id)
const State & state() const
void set_error(uint16_t error)
turbomath::Quaternion attitude
void log(CommLink::LogSeverity severity, const char *fmt,...)
turbomath::Vector angular_velocity
StateManager state_manager_
void calculate_equilbrium_torque_from_rc()
CommandManager command_manager_