We don't need to expose to other libraries how each backend is
implemented. AP_Baro.h is the main header, included by other libraries.
Instead of including each backend in the main header, move them to where
they are needed. Additionally standardize the order and how we include
the headers.
The advantages are:
- Internals of each backend is not exposed outside of the
library
- Faster incremental builds since we don't need to recompile
whoever includes AP_Baro.h because a backend changed
The configuration of MS5637 is different from MS5611 in 2 ways:
- The PROM is of 112 bytes rather than 128
- The CRC is located in the first MSB of the first word, not the
last one
For CRC calculation we also need to zero out the last (missing) word.
This renames _check_crc() to _read_prom(), which returns false when the
PROM doesn't contain valid data. It also makes it virtual so MS5637 can
override it. This also moves the PROM read to be all in the same place
rather than split between the CRC field and coefficient fields. Finally
calculate_crc() is renamed to crc4() to be shorter and add info on what
it does.
On MS5637 we will need to override the method to read and calculate the
PROM's crc. Thus we need a 2-phase init.
It also makes the constructor of AP_Baro_MS56XX protected since only the
derived classes should instantiate the base one.
commands_logic.cpp: In member function 'bool
Copter::verify_within_distance()':
commands_logic.cpp:770:21: warning: comparison between signed and
unsigned integer expressions [-Wsign-compare]
if (wp_distance < MAX(condition_value,0)) {
^
The problem with the current MIN/MAX macros is that they evaluate twice
the arguments. For example, these cases provide unintended results:
// a is incremented twice
a = MIN(a++, b);
// foo() with side-effects
a = MIN(foo(), b);
The alternative implementation here was provided by Daniel Frenzel using
template function. It doesn't have type safety as std::min and std::max,
but adding type safety would mean to check case by case what would be a
reasonable type and add proper casts. Here the arguments for MIN and MAX
can have different types and the return type is deduced from the
expression in the function.
Inspecting the current callers no place was found with the unintended
results above, but some in which now we don't calculate twice the
parameters will benefit from this new version. Examples:
float velocity_max = MIN(_pos_control.get_speed_xy(), safe_sqrt(0.5f*_pos_control.get_accel_xy()*_radius));
float acro_level_mix = constrain_float(1-MAX(MAX(abs(roll_in), abs(pitch_in)), abs(yaw_in))/4500.0, 0, 1)*ahrs.cos_pitch()
accel_x_cmss = (GRAVITY_MSS * 100) * (-(_ahrs.cos_yaw() * _ahrs.sin_pitch() / MAX(_ahrs.cos_pitch(),0.5f)) - _ahrs.sin_yaw() * _ahrs.sin_roll() / MAX(_ahrs.cos_roll(),0.5f));
track_leash_slack = MIN(_track_leash_length*(leash_z-track_error_z)/leash_z, _track_leash_length*(leash_xy-track_error_xy)/leash_xy);
RC_Channel_aux::move_servo(RC_Channel_aux::k_sprayer_pump, MIN(MAX(ground_speed * _pump_pct_1ms, 100 *_pump_min_pct),10000),0,10000);
The problem with using min() and max() is that they conflict with some
C++ headers. Name the macros in uppercase instead. We may go case by
case later converting them to be typesafe.
Changes generated with:
git ls-files '*.cpp' '*.h' -z | xargs -0 sed -i 's/\([^_[:alnum:]]\)max(/\1MAX(/g'
git ls-files '*.cpp' '*.h' -z | xargs -0 sed -i 's/\([^_[:alnum:]]\)min(/\1MIN(/g'
This useful when using X forwarding, as mavproxy can start to quickly, and then break the sim enviorment. If the argument isn't used there is no change in behaviour
As commented in 8218140 ("AP_Common: add scanf format macro"), "FORMAT"
was a bad name for this macro since there's also the scanf. Rename to
FMT_PRINTF to follow the scanf name.
Only compiled on Bebop, the constructor will need to be modified to
pass the pwm chip number and to create a PWM_Sysfs instead of a PWM_Sysfs_Bebop
in case it is used on a mainline linux board
Currently, the default behaviour on linux boards tries to
write LED gpios with fixed values among them. There is no way
to declare that there are no LED GPIOs.
This commit moves the declaration of the LED Gpios in AP_HAL_Boards.h
and makes AP_Notify do nothing if no LED gpio was declared
- Make error path in constructor shorter and earlier. It's calling
panic() so there's no reason to do anything else
- We don't need to check variable for NULL when calling free()
- Change set/get_polarity to use a virtual function; this allows us
not to fail silently if _polarity_path is NULL for PWM_Sysfs.
PWM_Sysfs_Bebop just overrides this method and implement an empty
version.
Modify existing class to create a PWM_Sysfs_Base class and derive it for
Bebop and Pwm_Sysfs (mainline kernel)
use asprintf for path allocation since it doesn't cost so much and is done
only at startup
Note that the constructor of the 2 classes : PWM_Sysfs and PWM_Sysfs_Bebop
allocate the paths and the constructor and desctuctor of class PWM_Sysfs_Base
frees them.
only keep in memory the paths that are needed later, i.e free _export_path,
_duty_path. The remaining path are freed in the destructor