param.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 #pragma GCC diagnostic ignored "-Wstrict-aliasing"
33 
34 #include <stdbool.h>
35 #include <stdint.h>
36 #include <string.h>
37 
38 #include "board.h"
39 #include "mixer.h"
40 
41 #include "param.h"
42 
43 #include "rosflight.h"
44 
45 namespace rosflight_firmware
46 {
47 
49  RF_(_rf)
50 {
51  for (uint16_t id = 0; id < PARAMS_COUNT; id++)
52  callbacks[id] = NULL;
53 }
54 
55 // local function definitions
56 void Params::init_param_int(uint16_t id, const char name[PARAMS_NAME_LENGTH], int32_t value)
57 {
58  memcpy(params.names[id], name, PARAMS_NAME_LENGTH);
59  params.values[id].ivalue = value;
61 }
62 
63 void Params::init_param_float(uint16_t id, const char name[PARAMS_NAME_LENGTH], float value)
64 {
65  memcpy(params.names[id], name, PARAMS_NAME_LENGTH);
66  params.values[id].fvalue = value;
68 }
69 
71 {
72  uint8_t chk = 0;
73  const char *p;
74 
75  for (p = reinterpret_cast<const char *>(&params.values);
76  p < reinterpret_cast<const char *>(&params.values) + 4*PARAMS_COUNT; p++)
77  chk ^= *p;
78  for (p = reinterpret_cast<const char *>(&params.names);
79  p < reinterpret_cast<const char *>(&params.names) + PARAMS_COUNT*PARAMS_NAME_LENGTH; p++)
80  chk ^= *p;
81  for (p = reinterpret_cast<const char *>(&params.types);
82  p < reinterpret_cast<const char *>(&params.types) + PARAMS_COUNT; p++)
83  chk ^= *p;
84 
85  return chk;
86 }
87 
88 
89 // function definitions
91 {
93  if (!read())
94  {
95  set_defaults();
96  write();
97  }
98 }
99 
101 {
102  /******************************/
103  /*** HARDWARE CONFIGURATION ***/
104  /******************************/
105  init_param_int(PARAM_BAUD_RATE, "BAUD_RATE",
106  921600); // Baud rate of MAVlink communication with onboard computer | 9600 | 921600
107  init_param_int(PARAM_SERIAL_DEVICE, "SERIAL_DEVICE", 0); // Serial Port (for supported devices) | 0 | 3
108 
109  /*****************************/
110  /*** MAVLINK CONFIGURATION ***/
111  /*****************************/
112  init_param_int(PARAM_SYSTEM_ID, "SYS_ID", 1); // Mavlink System ID | 1 | 255
113  init_param_int(PARAM_STREAM_HEARTBEAT_RATE, "STRM_HRTBT", 1); // Rate of heartbeat streaming (Hz) | 0 | 1000
114  init_param_int(PARAM_STREAM_STATUS_RATE, "STRM_STATUS", 10); // Rate of status streaming (Hz) | 0 | 1000
115 
116  init_param_int(PARAM_STREAM_ATTITUDE_RATE, "STRM_ATTITUDE", 200); // Rate of attitude stream (Hz) | 0 | 1000
117  init_param_int(PARAM_STREAM_IMU_RATE, "STRM_IMU", 250); // Rate of IMU stream (Hz) | 0 | 1000
118  init_param_int(PARAM_STREAM_MAG_RATE, "STRM_MAG", 50); // Rate of magnetometer stream (Hz) | 0 | 75
119  init_param_int(PARAM_STREAM_BARO_RATE, "STRM_BARO", 50); // Rate of barometer stream (Hz) | 0 | 100
120  init_param_int(PARAM_STREAM_AIRSPEED_RATE, "STRM_AIRSPEED", 50); // Rate of airspeed stream (Hz) | 0 | 50
121  init_param_int(PARAM_STREAM_SONAR_RATE, "STRM_SONAR", 40); // Rate of sonar stream (Hz) | 0 | 40
122  init_param_int(PARAM_STREAM_GNSS_RATE, "STRM_GNSS", 1000); // Maximum rate of GNSS stream (Hz) | 0 | 10
123  init_param_int(PARAM_STREAM_GNSS_RAW_RATE, "STRM_GNSS_RAW", 0); //Rate of GNSS raw stream (Hz) | 0 | 10
124 
125  init_param_int(PARAM_STREAM_OUTPUT_RAW_RATE, "STRM_SERVO", 50); // Rate of raw output stream | 0 | 490
126  init_param_int(PARAM_STREAM_RC_RAW_RATE, "STRM_RC", 50); // Rate of raw RC input stream | 0 | 50
127 
128  /********************************/
129  /*** CONTROLLER CONFIGURATION ***/
130  /********************************/
131  init_param_float(PARAM_MAX_COMMAND, "PARAM_MAX_CMD", 1.0); // saturation point for PID controller output | 0 | 1.0
132 
133  init_param_float(PARAM_PID_ROLL_RATE_P, "PID_ROLL_RATE_P", 0.070f); // Roll Rate Proportional Gain | 0.0 | 1000.0
134  init_param_float(PARAM_PID_ROLL_RATE_I, "PID_ROLL_RATE_I", 0.000f); // Roll Rate Integral Gain | 0.0 | 1000.0
135  init_param_float(PARAM_PID_ROLL_RATE_D, "PID_ROLL_RATE_D", 0.000f); // Rall Rate Derivative Gain | 0.0 | 1000.0
136 
137  init_param_float(PARAM_PID_PITCH_RATE_P, "PID_PITCH_RATE_P", 0.070f); // Pitch Rate Proporitional Gain | 0.0 | 1000.0
138  init_param_float(PARAM_PID_PITCH_RATE_I, "PID_PITCH_RATE_I", 0.0000f); // Pitch Rate Integral Gain | 0.0 | 1000.0
139  init_param_float(PARAM_PID_PITCH_RATE_D, "PID_PITCH_RATE_D", 0.0000f); // Pitch Rate Derivative Gain | 0.0 | 1000.0
140 
141  init_param_float(PARAM_PID_YAW_RATE_P, "PID_YAW_RATE_P", 0.25f); // Yaw Rate Proporitional Gain | 0.0 | 1000.0
142  init_param_float(PARAM_PID_YAW_RATE_I, "PID_YAW_RATE_I", 0.0f); // Yaw Rate Integral Gain | 0.0 | 1000.0
143  init_param_float(PARAM_PID_YAW_RATE_D, "PID_YAW_RATE_D", 0.0f); // Yaw Rate Derivative Gain | 0.0 | 1000.0
144 
145  init_param_float(PARAM_PID_ROLL_ANGLE_P, "PID_ROLL_ANG_P", 0.15f); // Roll Angle Proporitional Gain | 0.0 | 1000.0
146  init_param_float(PARAM_PID_ROLL_ANGLE_I, "PID_ROLL_ANG_I", 0.0f); // Roll Angle Integral Gain | 0.0 | 1000.0
147  init_param_float(PARAM_PID_ROLL_ANGLE_D, "PID_ROLL_ANG_D", 0.05f); // Roll Angle Derivative Gain | 0.0 | 1000.0
148 
149  init_param_float(PARAM_PID_PITCH_ANGLE_P, "PID_PITCH_ANG_P", 0.15f); // Pitch Angle Proporitional Gain | 0.0 | 1000.0
150  init_param_float(PARAM_PID_PITCH_ANGLE_I, "PID_PITCH_ANG_I", 0.0f); // Pitch Angle Integral Gain | 0.0 | 1000.0
151  init_param_float(PARAM_PID_PITCH_ANGLE_D, "PID_PITCH_ANG_D", 0.05f); // Pitch Angle Derivative Gain | 0.0 | 1000.0
152 
153  init_param_float(PARAM_X_EQ_TORQUE, "X_EQ_TORQUE",
154  0.0f); // Equilibrium torque added to output of controller on x axis | -1.0 | 1.0
155  init_param_float(PARAM_Y_EQ_TORQUE, "Y_EQ_TORQUE",
156  0.0f); // Equilibrium torque added to output of controller on y axis | -1.0 | 1.0
157  init_param_float(PARAM_Z_EQ_TORQUE, "Z_EQ_TORQUE",
158  0.0f); // Equilibrium torque added to output of controller on z axis | -1.0 | 1.0
159 
160  init_param_float(PARAM_PID_TAU, "PID_TAU",
161  0.05f); // Dirty Derivative time constant - See controller documentation | 0.0 | 1.0
162 
163 
164  /*************************/
165  /*** PWM CONFIGURATION ***/
166  /*************************/
167  init_param_int(PARAM_MOTOR_PWM_SEND_RATE, "MOTOR_PWM_UPDATE",
168  0); // Overrides default PWM rate specified by mixer if non-zero - Requires reboot to take effect | 0 | 490
170  0.1); // min throttle command sent to motors when armed (Set above 0.1 to spin when armed) | 0.0 | 1.0
172  0.3); // Throttle sent to motors in failsafe condition (set just below hover throttle) | 0.0 | 1.0
173  init_param_int(PARAM_SPIN_MOTORS_WHEN_ARMED, "ARM_SPIN_MOTORS", true); // Enforce MOTOR_IDLE_THR | 0 | 1
174 
175  /*******************************/
176  /*** ESTIMATOR CONFIGURATION ***/
177  /*******************************/
178  init_param_int(PARAM_INIT_TIME, "FILTER_INIT_T", 3000); // Time in ms to initialize estimator | 0 | 100000
179  init_param_float(PARAM_FILTER_KP, "FILTER_KP",
180  0.5f); // estimator proportional gain - See estimator documentation | 0 | 10.0
181  init_param_float(PARAM_FILTER_KI, "FILTER_KI",
182  0.01f); // estimator integral gain - See estimator documentation | 0 | 1.0
184  10.0f); // estimator proportional gain on external attitude correction - See estimator documentation | 0 | 1.0
185 
186  init_param_int(PARAM_FILTER_USE_QUAD_INT, "FILTER_QUAD_INT",
187  1); // Perform a quadratic averaging of LPF gyro data prior to integration (adds ~20 us to estimation loop on F1 processors) | 0 | 1
188  init_param_int(PARAM_FILTER_USE_MAT_EXP, "FILTER_MAT_EXP",
189  1); // 1 - Use matrix exponential to improve gyro integration (adds ~90 us to estimation loop in F1 processors) 0 - use euler integration | 0 | 1
190  init_param_int(PARAM_FILTER_USE_ACC, "FILTER_USE_ACC",
191  1); // Use accelerometer to correct gyro integration drift (adds ~70 us to estimation loop) | 0 | 1
192 
193  init_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, "CAL_GYRO_ARM", false); // True if desired to calibrate gyros on arm | 0 | 1
194 
195  init_param_float(PARAM_GYRO_XY_ALPHA, "GYROXY_LPF_ALPHA",
196  0.3f); // Low-pass filter constant on gyro X and Y axes - See estimator documentation | 0 | 1.0
197  init_param_float(PARAM_GYRO_Z_ALPHA, "GYROZ_LPF_ALPHA",
198  0.3f); // Low-pass filter constant on gyro Z axis - See estimator documentation | 0 | 1.0
199  init_param_float(PARAM_ACC_ALPHA, "ACC_LPF_ALPHA",
200  0.5f); // Low-pass filter constant on all accel axes - See estimator documentation | 0 | 1.0
201 
202  init_param_float(PARAM_GYRO_X_BIAS, "GYRO_X_BIAS", 0.0f); // Constant x-bias of gyroscope readings | -1.0 | 1.0
203  init_param_float(PARAM_GYRO_Y_BIAS, "GYRO_Y_BIAS", 0.0f); // Constant y-bias of gyroscope readings | -1.0 | 1.0
204  init_param_float(PARAM_GYRO_Z_BIAS, "GYRO_Z_BIAS", 0.0f); // Constant z-bias of gyroscope readings | -1.0 | 1.0
205  init_param_float(PARAM_ACC_X_BIAS, "ACC_X_BIAS", 0.0f); // Constant x-bias of accelerometer readings | -2.0 | 2.0
206  init_param_float(PARAM_ACC_Y_BIAS, "ACC_Y_BIAS", 0.0f); // Constant y-bias of accelerometer readings | -2.0 | 2.0
207  init_param_float(PARAM_ACC_Z_BIAS, "ACC_Z_BIAS", 0.0f); // Constant z-bias of accelerometer readings | -2.0 | 2.0
208  init_param_float(PARAM_ACC_X_TEMP_COMP, "ACC_X_TEMP_COMP",
209  0.0f); // Linear x-axis temperature compensation constant | -2.0 | 2.0
210  init_param_float(PARAM_ACC_Y_TEMP_COMP, "ACC_Y_TEMP_COMP",
211  0.0f); // Linear y-axis temperature compensation constant | -2.0 | 2.0
212  init_param_float(PARAM_ACC_Z_TEMP_COMP, "ACC_Z_TEMP_COMP",
213  0.0f); // Linear z-axis temperature compensation constant | -2.0 | 2.0
214 
215  init_param_float(PARAM_MAG_A11_COMP, "MAG_A11_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0
216  init_param_float(PARAM_MAG_A12_COMP, "MAG_A12_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
217  init_param_float(PARAM_MAG_A13_COMP, "MAG_A13_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
218  init_param_float(PARAM_MAG_A21_COMP, "MAG_A21_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
219  init_param_float(PARAM_MAG_A22_COMP, "MAG_A22_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0
220  init_param_float(PARAM_MAG_A23_COMP, "MAG_A23_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
221  init_param_float(PARAM_MAG_A31_COMP, "MAG_A31_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
222  init_param_float(PARAM_MAG_A32_COMP, "MAG_A32_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0
223  init_param_float(PARAM_MAG_A33_COMP, "MAG_A33_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0
224  init_param_float(PARAM_MAG_X_BIAS, "MAG_X_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0
225  init_param_float(PARAM_MAG_Y_BIAS, "MAG_Y_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0
226  init_param_float(PARAM_MAG_Z_BIAS, "MAG_Z_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0
227 
228  init_param_float(PARAM_BARO_BIAS, "BARO_BIAS", 0.0f); // Barometer measurement bias (Pa) | 0 | inf
229  init_param_float(PARAM_GROUND_LEVEL, "GROUND_LEVEL", 1387.0f); // Altitude of ground level (m) | -1000 | 10000
230 
231  init_param_float(PARAM_DIFF_PRESS_BIAS, "DIFF_PRESS_BIAS", 0.0f); // Differential Pressure Bias (Pa) | -10 | 10
232 
233  /************************/
234  /*** RC CONFIGURATION ***/
235  /************************/
236  init_param_int(PARAM_RC_TYPE, "RC_TYPE", 0); // Type of RC input 0 - PPM, 1 - SBUS | 0 | 1
237  init_param_int(PARAM_RC_X_CHANNEL, "RC_X_CHN", 0); // RC input channel mapped to x-axis commands [0 - indexed] | 0 | 3
238  init_param_int(PARAM_RC_Y_CHANNEL, "RC_Y_CHN", 1); // RC input channel mapped to y-axis commands [0 - indexed] | 0 | 3
239  init_param_int(PARAM_RC_Z_CHANNEL, "RC_Z_CHN", 3); // RC input channel mapped to z-axis commands [0 - indexed] | 0 | 3
240  init_param_int(PARAM_RC_F_CHANNEL, "RC_F_CHN", 2); // RC input channel mapped to F-axis commands [0 - indexed] | 0 | 3
242  4); // RC switch mapped to attitude override [0 indexed, -1 to disable] | 4 | 7
244  4); // RC switch channel mapped to throttle override [0 indexed, -1 to disable] | 4 | 7
246  -1); // RC switch channel mapped to attitude control type [0 indexed, -1 to disable] | 4 | 7
247  init_param_int(PARAM_RC_ARM_CHANNEL, "ARM_CHANNEL",
248  -1); // RC switch channel mapped to arming (only if PARAM_ARM_STICKS is false) [0 indexed, -1 to disable] | 4 | 7
249  init_param_int(PARAM_RC_NUM_CHANNELS, "RC_NUM_CHN", 6); // number of RC input channels | 1 | 8
250 
251  init_param_int(PARAM_RC_SWITCH_5_DIRECTION, "SWITCH_5_DIR", 1); // RC switch 5 toggle direction | -1 | 1
252  init_param_int(PARAM_RC_SWITCH_6_DIRECTION, "SWITCH_6_DIR", 1); // RC switch 6 toggle direction | -1 | 1
253  init_param_int(PARAM_RC_SWITCH_7_DIRECTION, "SWITCH_7_DIR", 1); // RC switch 7 toggle direction | -1 | 1
254  init_param_int(PARAM_RC_SWITCH_8_DIRECTION, "SWITCH_8_DIR", 1); // RC switch 8 toggle direction | -1 | 1
255 
257  0.1); // RC stick deviation from center for overrride | 0.0 | 1.0
258  init_param_int(PARAM_OVERRIDE_LAG_TIME, "OVRD_LAG_TIME",
259  1000); // RC stick deviation lag time before returning control (ms) | 0 | 100000
261  true); // Take minimum throttle between RC and computer at all times | 0 | 1
262 
263  init_param_int(PARAM_RC_ATTITUDE_MODE, "RC_ATT_MODE",
264  1); // Attitude mode for RC sticks (0: rate, 1: angle). Overridden if RC_ATT_CTRL_CHN is set. | 0 | 1
265  init_param_float(PARAM_RC_MAX_ROLL, "RC_MAX_ROLL",
266  0.786f); // Maximum roll angle command sent by full deflection of RC sticks | 0.0 | 3.14159
267  init_param_float(PARAM_RC_MAX_PITCH, "RC_MAX_PITCH",
268  0.786f); // Maximum pitch angle command sent by full stick deflection of RC sticks | 0.0 | 3.14159
269  init_param_float(PARAM_RC_MAX_ROLLRATE, "RC_MAX_ROLLRATE",
270  3.14159f); // Maximum roll rate command sent by full stick deflection of RC sticks | 0.0 | 9.42477796077
271  init_param_float(PARAM_RC_MAX_PITCHRATE, "RC_MAX_PITCHRATE",
272  3.14159f); // Maximum pitch command sent by full stick deflection of RC sticks | 0.0 | 3.14159
273  init_param_float(PARAM_RC_MAX_YAWRATE, "RC_MAX_YAWRATE",
274  1.507f); // Maximum pitch command sent by full stick deflection of RC sticks | 0.0 | 3.14159
275 
276  /***************************/
277  /*** FRAME CONFIGURATION ***/
278  /***************************/
279  init_param_int(PARAM_MIXER, "MIXER", Mixer::INVALID_MIXER); // Which mixer to choose - See Mixer documentation | 0 | 10
280 
281  init_param_int(PARAM_FIXED_WING, "FIXED_WING",
282  false); // switches on passthrough commands for fixedwing operation | 0 | 1
283  init_param_int(PARAM_ELEVATOR_REVERSE, "ELEVATOR_REV", 0); // reverses elevator servo output | 0 | 1
284  init_param_int(PARAM_AILERON_REVERSE, "AIL_REV", 0); // reverses aileron servo output | 0 | 1
285  init_param_int(PARAM_RUDDER_REVERSE, "RUDDER_REV", 0); // reverses rudder servo output | 0 | 1
286 
287  init_param_float(PARAM_FC_ROLL, "FC_ROLL",
288  0.0f); // roll angle (deg) of flight controller wrt to aircraft body | -180 | 180
289  init_param_float(PARAM_FC_PITCH, "FC_PITCH",
290  0.0f); // pitch angle (deg) of flight controller wrt to aircraft body | -180 | 180
291  init_param_float(PARAM_FC_YAW, "FC_YAW",
292  0.0f); // yaw angle (deg) of flight controller wrt to aircraft body | -180 | 180
293 
294 
295  /********************/
296  /*** ARMING SETUP ***/
297  /********************/
298  init_param_float(PARAM_ARM_THRESHOLD, "ARM_THRESHOLD",
299  0.15); // RC deviation from max/min in yaw and throttle for arming and disarming check (us) | 0 | 500
300 
301  /************************/
302  /*** OFFBOARD CONTROL ***/
303  /************************/
304  init_param_int(PARAM_OFFBOARD_TIMEOUT, "OFFBOARD_TIMEOUT",
305  100); // Timeout in milliseconds for offboard commands, after which RC override is activated | 0 | 100000
306 }
307 
308 void Params::add_callback(std::function<void(int)> callback, uint16_t param_id)
309 {
310  callbacks[param_id] = callback;
311  callback(param_id);
312 }
313 
314 bool Params::read(void)
315 {
316  if (!RF_.board_.memory_read(&params, sizeof(params_t)))
317  return false;
318 
320  return false;
321 
322  if (params.size != sizeof(params_t) || params.magic_be != 0xBE || params.magic_ef != 0xEF)
323  return false;
324 
325  if (compute_checksum() != params.chk)
326  return false;
327 
328  return true;
329 }
330 
331 bool Params::write(void)
332 {
334  params.size = sizeof(params_t);
335  params.magic_be = 0xBE;
336  params.magic_ef = 0xEF;
338 
339  if (!RF_.board_.memory_write(&params, sizeof(params_t)))
340  return false;
341  return true;
342 }
343 
344 void Params::change_callback(uint16_t id)
345 {
346  // call the callback function
347  if (callbacks[id])
348  callbacks[id](id);
349 }
350 
352 {
353  for (uint16_t id = 0; id < PARAMS_COUNT; id++)
354  {
355  bool match = true;
356  for (uint8_t i = 0; i < PARAMS_NAME_LENGTH; i++)
357  {
358  // compare each character
359  if (name[i] != params.names[id][i])
360  {
361  match = false;
362  break;
363  }
364 
365  // stop comparing if end of string is reached
366  if (params.names[id][i] == '\0')
367  break;
368  }
369 
370  if (match)
371  return id;
372  }
373 
374  return PARAMS_COUNT;
375 }
376 
377 bool Params::set_param_int(uint16_t id, int32_t value)
378 {
379  if (id < PARAMS_COUNT && value != params.values[id].ivalue)
380  {
381  params.values[id].ivalue = value;
382  change_callback(id);
384  return true;
385  }
386  return false;
387 }
388 
389 bool Params::set_param_float(uint16_t id, float value)
390 {
391  if (id < PARAMS_COUNT && value != params.values[id].fvalue)
392  {
393  params.values[id].fvalue = value;
394  change_callback(id);
396  return true;
397  }
398  return false;
399 }
400 
401 bool Params::set_param_by_name_int(const char name[PARAMS_NAME_LENGTH], int32_t value)
402 {
403  uint16_t id = lookup_param_id(name);
404  return set_param_int(id, value);
405 }
406 
408 {
409  return set_param_by_name_int(name, reinterpret_cast<int32_t &>(value));
410 }
411 }
char names[PARAMS_COUNT][PARAMS_NAME_LENGTH]
Definition: param.h:250
#define GIT_VERSION_HASH
Definition: param.h:40
virtual void memory_init()=0
virtual bool memory_write(const void *src, size_t len)=0
uint16_t lookup_param_id(const char name[PARAMS_NAME_LENGTH])
Gets the id of a parameter from its name.
Definition: param.cpp:351
param_type_t types[PARAMS_COUNT]
Definition: param.h:251
void set_defaults(void)
Set all parameters to default values.
Definition: param.cpp:100
void change_callback(uint16_t id)
Callback for executing actions that need to be taken when a parameter value changes.
Definition: param.cpp:344
bool read(void)
Read parameter values from non-volatile memory.
Definition: param.cpp:314
void init_param_int(uint16_t id, const char name[PARAMS_NAME_LENGTH], int32_t value)
Definition: param.cpp:56
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 send_param_value(uint16_t param_id)
static constexpr uint8_t PARAMS_NAME_LENGTH
Definition: param.h:234
void add_callback(std::function< void(int)> callback, uint16_t param_id)
Definition: param.cpp:308
Params(ROSflight &_rf)
Definition: param.cpp:48
virtual bool memory_read(void *dest, size_t len)=0
bool set_param_by_name_int(const char name[PARAMS_NAME_LENGTH], int32_t value)
Sets the value of a parameter by name and calls the parameter change callback.
Definition: param.cpp:401
#define NULL
Definition: usbd_def.h:50
void init_param_float(uint16_t id, const char name[PARAMS_NAME_LENGTH], float value)
Definition: param.cpp:63
void init()
Initialize parameter values.
Definition: param.cpp:90
bool set_param_by_name_float(const char name[PARAMS_NAME_LENGTH], float value)
Sets the value of a floating point parameter by name and calls the parameter change callback...
Definition: param.cpp:407
uint8_t compute_checksum(void)
Definition: param.cpp:70
bool write(void)
Write current parameter values to non-volatile memory.
Definition: param.cpp:331
bool set_param_int(uint16_t id, int32_t value)
Sets the value of a parameter by ID and calls the parameter change callback.
Definition: param.cpp:377
std::function< void(int)> callbacks[PARAMS_COUNT]
Definition: param.h:257
param_value_t values[PARAMS_COUNT]
Definition: param.h:249


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