controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include <stdint.h>
33 #include <stdbool.h>
34 
35 #include "command_manager.h"
36 #include "estimator.h"
37 #include "rosflight.h"
38 
39 #include "controller.h"
40 
41 namespace rosflight_firmware
42 {
43 
45  RF_(rf)
46 {
47  RF_.params_.add_callback([this](uint16_t param_id)
48  {
49  this->param_change_callback(param_id);
51  RF_.params_.add_callback([this](uint16_t param_id)
52  {
53  this->param_change_callback(param_id);
55  RF_.params_.add_callback([this](uint16_t param_id)
56  {
57  this->param_change_callback(param_id);
59  RF_.params_.add_callback([this](uint16_t param_id)
60  {
61  this->param_change_callback(param_id);
63  RF_.params_.add_callback([this](uint16_t param_id)
64  {
65  this->param_change_callback(param_id);
67  RF_.params_.add_callback([this](uint16_t param_id)
68  {
69  this->param_change_callback(param_id);
71  RF_.params_.add_callback([this](uint16_t param_id)
72  {
73  this->param_change_callback(param_id);
75  RF_.params_.add_callback([this](uint16_t param_id)
76  {
77  this->param_change_callback(param_id);
79  RF_.params_.add_callback([this](uint16_t param_id)
80  {
81  this->param_change_callback(param_id);
83  RF_.params_.add_callback([this](uint16_t param_id)
84  {
85  this->param_change_callback(param_id);
87  RF_.params_.add_callback([this](uint16_t param_id)
88  {
89  this->param_change_callback(param_id);
91  RF_.params_.add_callback([this](uint16_t param_id)
92  {
93  this->param_change_callback(param_id);
95  RF_.params_.add_callback([this](uint16_t param_id)
96  {
97  this->param_change_callback(param_id);
99  RF_.params_.add_callback([this](uint16_t param_id)
100  {
101  this->param_change_callback(param_id);
103  RF_.params_.add_callback([this](uint16_t param_id)
104  {
105  this->param_change_callback(param_id);
107  RF_.params_.add_callback([this](uint16_t param_id)
108  {
109  this->param_change_callback(param_id);
110  }, PARAM_MAX_COMMAND);
111  RF_.params_.add_callback([this](uint16_t param_id)
112  {
113  this->param_change_callback(param_id);
114  }, PARAM_PID_TAU);
115 }
116 
118 {
119  prev_time_us_ = 0;
120 
122  float min = -max;
124 
128  max, min, tau);
132  max, min, tau);
136  max, min, tau);
140  max, min, tau);
144  max, min, tau);
145 }
146 
148 {
149  // Time calculation
150  if (prev_time_us_ == 0)
151  {
153  return;
154  }
155 
156  int32_t dt_us = (RF_.estimator_.state().timestamp_us - prev_time_us_);
157  if (dt_us < 0)
158  {
160  return;
161  }
163 
164  // Check if integrators should be updated
166  bool update_integrators = (RF_.state_manager_.state().armed)
167  && (RF_.command_manager_.combined_control().F.value > 0.1f) && dt_us < 10000;
168 
169  // Run the PID loops
171  update_integrators);
172 
173  // Add feedforward torques
178 }
179 
181 {
182  // Make sure we are disarmed
183  if (!(RF_.state_manager_.state().armed))
184  {
185  // Tell the user that we are doing a equilibrium torque calibration
186  RF_.comm_manager_.log(CommLink::LogSeverity::LOG_WARNING, "Capturing equilbrium offsets from RC");
187 
188  // Prepare for calibration
189  // artificially tell the flight controller it is leveled
190  Estimator::State fake_state;
191  fake_state.angular_velocity.x = 0.0f;
192  fake_state.angular_velocity.y = 0.0f;
193  fake_state.angular_velocity.z = 0.0f;
194 
195  fake_state.attitude.x = 0.0f;
196  fake_state.attitude.y = 0.0f;
197  fake_state.attitude.z = 0.0f;
198  fake_state.attitude.w = 1.0f;
199 
200  fake_state.roll = 0.0f;
201  fake_state.pitch = 0.0f;
202  fake_state.yaw = 0.0f;
203 
204  // pass the rc_control through the controller
205  // dt is zero, so what this really does is applies the P gain with the settings
206  // your RC transmitter, which if it flies level is a really good guess for
207  // the static offset torques
208  turbomath::Vector pid_output = run_pid_loops(0, fake_state, RF_.command_manager_.rc_control(), false);
209 
210  // the output from the controller is going to be the static offsets
214 
215  RF_.comm_manager_.log(CommLink::LogSeverity::LOG_WARNING, "Equilibrium torques found and applied.");
216  RF_.comm_manager_.log(CommLink::LogSeverity::LOG_WARNING, "Please zero out trims on your transmitter");
217  }
218  else
219  {
220  RF_.comm_manager_.log(CommLink::LogSeverity::LOG_WARNING, "Cannot perform equilibrium offset calibration while armed");
221  }
222 }
223 
224 void Controller::param_change_callback(uint16_t param_id)
225 {
226  (void) param_id; // suppress unused parameter warning
227  init();
228 }
229 
230 turbomath::Vector Controller::run_pid_loops(uint32_t dt_us, const Estimator::State &state, const control_t &command,
231  bool update_integrators)
232 {
233  // Based on the control types coming from the command manager, run the appropriate PID loops
235 
236  float dt = 1e-6*dt_us;
237 
238  // ROLL
239  if (command.x.type == RATE)
240  out.x = roll_rate_.run(dt, state.angular_velocity.x, command.x.value, update_integrators);
241  else if (command.x.type == ANGLE)
242  out.x = roll_.run(dt, state.roll, command.x.value, update_integrators, state.angular_velocity.x);
243  else
244  out.x = command.x.value;
245 
246  // PITCH
247  if (command.y.type == RATE)
248  out.y = pitch_rate_.run(dt, state.angular_velocity.y, command.y.value, update_integrators);
249  else if (command.y.type == ANGLE)
250  out.y = pitch_.run(dt, state.pitch, command.y.value, update_integrators, state.angular_velocity.y);
251  else
252  out.y = command.y.value;
253 
254  // YAW
255  if (command.z.type == RATE)
256  out.z = yaw_rate_.run(dt, state.angular_velocity.z, command.z.value, update_integrators);
257  else
258  out.z = command.z.value;
259 
260  return out;
261 }
262 
264  kp_(0.0f),
265  ki_(0.0f),
266  kd_(0.0f),
267  max_(1.0f),
268  min_(-1.0f),
269  integrator_(0.0f),
270  differentiator_(0.0f),
271  prev_x_(0.0f),
272  tau_(0.05)
273 {}
274 
275 void Controller::PID::init(float kp, float ki, float kd, float max, float min, float tau)
276 {
277  kp_ = kp;
278  ki_ = ki;
279  kd_ = kd;
280  max_ = max;
281  min_ = min;
282  tau_ = tau;
283 }
284 
285 float Controller::PID::run(float dt, float x, float x_c, bool update_integrator)
286 {
287  float xdot;
288  if (dt > 0.0001f)
289  {
290  // calculate D term (use dirty derivative if we don't have access to a measurement of the derivative)
291  // The dirty derivative is a sort of low-pass filtered version of the derivative.
293  differentiator_ = (2.0f * tau_ - dt) / (2.0f * tau_ + dt) * differentiator_
294  + 2.0f / (2.0f * tau_ + dt) * (x - prev_x_);
295  xdot = differentiator_;
296  }
297  else
298  {
299  xdot = 0.0f;
300  }
301  prev_x_ = x;
302 
303  return run(dt, x, x_c, update_integrator, xdot);
304 }
305 
306 float Controller::PID::run(float dt, float x, float x_c, bool update_integrator, float xdot)
307 {
308  // Calculate Error
309  float error = x_c - x;
310 
311  // Initialize Terms
312  float p_term = error * kp_;
313  float i_term = 0.0f;
314  float d_term = 0.0f;
315 
316  // If there is a derivative term
317  if (kd_ > 0.0f)
318  {
319  d_term = kd_ * xdot;
320  }
321 
322  //If there is an integrator term and we are updating integrators
323  if ((ki_ > 0.0f) && update_integrator)
324  {
325  // integrate
326  integrator_ += error * dt;
327  // calculate I term
328  i_term = ki_ * integrator_;
329  }
330 
331  // sum three terms
332  float u = p_term - d_term + i_term;
333 
334  // Integrator anti-windup
336  float u_sat = (u > max_) ? max_ : (u < min_) ? min_ : u;
337  if (u != u_sat && fabs(i_term) > fabs(u - p_term + d_term) && ki_ > 0.0f)
338  integrator_ = (u_sat - p_term + d_term)/ki_;
339 
340  // Set output
341  return u_sat;
342 }
343 
344 } // namespace rosflight_firmware
void param_change_callback(uint16_t param_id)
Definition: controller.cpp:224
static volatile bool error
Definition: drv_i2c.c:92
const control_t & combined_control() const
float fabs(float x)
Definition: turbomath.cpp:571
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)
Definition: controller.cpp:230
bool set_param_float(uint16_t id, float value)
Sets the value of a floating point parameter by ID and calls the parameter callback.
Definition: param.cpp:389
void init(float kp, float ki, float kd, float max, float min, float tau)
Definition: controller.cpp:275
float get_param_float(uint16_t id) const
Get the value of a floating point parameter by id.
Definition: param.h:326
const State & state() const
Definition: estimator.h:62
float run(float dt, float x, float x_c, bool update_integrator)
Definition: controller.cpp:285
void add_callback(std::function< void(int)> callback, uint16_t param_id)
Definition: param.cpp:308
const State & state() const
Definition: state_manager.h:82
void set_error(uint16_t error)
turbomath::Quaternion attitude
Definition: estimator.h:53
void log(CommLink::LogSeverity severity, const char *fmt,...)
turbomath::Vector angular_velocity
Definition: estimator.h:52


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24