Skip to content

Commit

Permalink
checkpatch: Cleanup based on check_compliance.py
Browse files Browse the repository at this point in the history
This commit fixes a number of issues found while running
check_compliance.py against the codebase.

Signed-off-by: Kevin Townsend <kevin@ktownsend.com>
  • Loading branch information
microbuilder committed Sep 10, 2021
1 parent 7cb1cd4 commit 3a1bf08
Show file tree
Hide file tree
Showing 46 changed files with 923 additions and 904 deletions.
12 changes: 11 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,16 @@ $ twister --inline-logs -p mps2_an521 -T modules/lib/zscilib/tests

See the `tests` folder for further details.

To run compliance tests to make sure submitted code matches Zephyr PR
requirements, run this (updating `HEAD~2` for the number of commits to check,
or setting it to `origin/master..` to check everything):

```bash
$ ../../../zephyr/scripts/ci/check_compliance.py \
-m Gitlint -m Identity -m Nits -m pylint -m checkpatch \
-c HEAD~2..
```

### Debugging with QEMU

If you wish to debug using QEMU (and with minor variation actual hardware),
Expand Down Expand Up @@ -291,7 +301,6 @@ to ensure that the stack pointer is double-word aligned).
| Project | `zsl_vec_project` | x | x | | |
| To unit vector | `zsl_vec_to_unit` | x | x | | |
| Cross product | `zsl_vec_cross` | x | x | | |
| Wedge product | `zsl_vec_wedge` | | | | |
| Sum of squares | `zsl_vec_sum_of_sqrs` | x | x | | |
| Comp-wise mean | `zsl_vec_mean` | x | x | | |
| Arithmetic mean | `zsl_vec_ar_mean` | x | x | | |
Expand Down Expand Up @@ -332,6 +341,7 @@ to ensure that the stack pointer is double-word aligned).
| Transpose | `zsl_mtx_trans` | x | x | | |
| Adjoint 3x3 | `zsl_mtx_adjoint_3x3` | x | x | | |
| Adjoint | `zsl_mtx_adjoint` | x | x | | |
| Wedge product | `zsl_mtx_vec_wedge` | | x | | |
| Reduce | `zsl_mtx_reduce` | x | x | | Row+col removal |
| Reduce (iter) | `zsl_mtx_reduce_iter` | x | x | | Iterative ver. |
| Augment | `zsl_mtx_augm_diag` | x | x | | Adds row+col(s) |
Expand Down
5 changes: 2 additions & 3 deletions include/zsl/chemistry.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,8 @@
* @defgroup CHEMISTRY Chemistry
*
* @brief Chemistry functions.
*
* @{ */

* @{
*/

/**
* @file
Expand Down
12 changes: 6 additions & 6 deletions include/zsl/matrices.h
Original file line number Diff line number Diff line change
Expand Up @@ -512,7 +512,7 @@ int zsl_mtx_mult(struct zsl_mtx *ma, struct zsl_mtx *mb, struct zsl_mtx *mc);
* Matrices 'ma' and 'mb' must be compatibly shaped, meaning that
* 'ma' must have the same numbers of columns as there are rows
* in 'mb'. To use this function, 'mb' must be a square matrix.
* This function is destructive.
* This function is destructive.
*
* @param ma Pointer to the first input zsl_mtx.
* @param mb Pointer to the second input zsl_mtx.
Expand Down Expand Up @@ -594,19 +594,19 @@ int zsl_mtx_adjoint(struct zsl_mtx *m, struct zsl_mtx *ma);
#ifndef CONFIG_ZSL_SINGLE_PRECISION
/**
* @brief Calculates the wedge product of n-1 vectors of size n, which are the
* rows of the matrix 'm'. This n-1 vectors must be linearly independent.
* rows of the matrix 'm'. This n-1 vectors must be linearly independent.
*
* The wedge product is an extension of the cross product for dimension greater
* than 3. Given a set of n-1 vectors of size n, the wedge product calculates
* a n-dimensional vector that is perpendicular to all the others.
*
* @param m The input (n-1) x n matrix, with n > 3, whose rows are the
* linearly independent vectors to use in the wedge product.
* linearly independent vectors to use in the wedge product.
* @param v The output vector of dimension n, perpendicular to all the
* input vectors.
* input vectors.
*
* @return 0 if everything executed correctly, or -EINVAL if n > 3, or if
* the input matrix isn't of the form (n-1) x n.
* the input matrix isn't of the form (n-1) x n.
*/
int zsl_mtx_vec_wedge(struct zsl_mtx *m, struct zsl_vec *v);
#endif
Expand Down Expand Up @@ -805,7 +805,7 @@ int zsl_mtx_inv(struct zsl_mtx *m, struct zsl_mtx *mi);

/**
* @brief Calculates the Cholesky decomposition of a symmetric square matrix
* using the Cholesky–Crout algorithm.
* using the Cholesky–Crout algorithm.
*
* Computing the Cholesky decomposition of a symmetric square matrix M consists
* in finding a matrix L such that M = L * Lt (L multiplied by its transpose).
Expand Down
28 changes: 14 additions & 14 deletions include/zsl/orientation/ahrs.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@ struct zsl_attitude {
* same memory address to a @ref zsl_vec, allowing for vector functions
* to be used on the zsl_attitude values.
*
* @param a Pointer to the zsl_attitude struct to use.
* @param v Pointer to the zsl_vec struct to use.
* @param a Pointer to the zsl_attitude struct to use.
* @param v Pointer to the zsl_vec struct to use.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
Expand All @@ -92,8 +92,8 @@ int zsl_att_to_vec(struct zsl_attitude *a, struct zsl_vec *v);
* @brief Converts the input @ref zsl_attitude, expessed in degrees, to it's
* equivalent in radians in the output @ref zsl_euler.
*
* @param a Pointer to the zsl_attitued struct to use.
* @param e Pointer to the zsl_euler struct to use.
* @param a Pointer to the zsl_attitued struct to use.
* @param e Pointer to the zsl_euler struct to use.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
Expand All @@ -103,8 +103,8 @@ int zsl_att_to_euler(struct zsl_attitude *a, struct zsl_euler *e);
* @brief Converts the input @ref zsl_euler, expessed in radians, to it's
* equivalent in degrees in the output @ref zsl_attitude.
*
* @param e Pointer to the zsl_euler struct to use.
* @param a Pointer to the zsl_attitued struct to use.
* @param e Pointer to the zsl_euler struct to use.
* @param a Pointer to the zsl_attitued struct to use.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
Expand All @@ -114,9 +114,9 @@ int zsl_att_from_euler(struct zsl_euler *e, struct zsl_attitude *a);
* @brief Converts a three-axis accelerometer (in m/s^2) and a three-axis
* magnetometer sample (in micro-Tesla) to attitude.
*
* @param accel Acceleration triplet in m/s^2.
* @param mag Magnetometer triplet in micro-Tesla.
* @param a Pointer the the output @ref zsl_attitude struct.
* @param accel Acceleration triplet in m/s^2.
* @param mag Magnetometer triplet in micro-Tesla.
* @param a Pointer the the output @ref zsl_attitude struct.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
Expand All @@ -127,8 +127,8 @@ int zsl_att_from_accelmag(struct zsl_vec *accel, struct zsl_vec *mag,
* @brief Converts a three-axis accelerometer sample (in m/s^2) to roll and
* pitch.
*
* @param accel Acceleration triplet in m/s^2.
* @param a Pointer the the output @ref zsl_attitude struct.
* @param accel Acceleration triplet in m/s^2.
* @param a Pointer the the output @ref zsl_attitude struct.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
Expand All @@ -137,9 +137,9 @@ int zsl_att_from_accel(struct zsl_vec *accel, struct zsl_attitude *a);
/**
* @brief Calculates the angle between two accelerometers.
*
* @param a1 First acceleration triplet in m/s^2.
* @param a2 First acceleration triplet in m/s^2.
* @param b Angle between the accelerometers, in radians.
* @param a1 First acceleration triplet in m/s^2.
* @param a2 First acceleration triplet in m/s^2.
* @param b Angle between the accelerometers, in radians.
*
* @return 0 if everything executed correctly, otherwise a negative error code
* if the accelerometer data is not tridimensional.
Expand Down
17 changes: 9 additions & 8 deletions include/zsl/orientation/compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,8 @@
* 2° 13' 0" East) to decimal degrees (2.216667 in this case).
*
* @ingroup ORIENTATION
* @{ */
* @{
*/

/**
* @file
Expand Down Expand Up @@ -77,7 +78,7 @@ extern "C" {
* @param dd Pointer to the output decimal degrees value.
*
* @return 0 if everything executed normally, or a negative error code if the
* dimension of the magnetometer vector is not three.
* dimension of the magnetometer vector is not three.
*/
int zsl_comp_dms_to_dd(zsl_real_t d, zsl_real_t m, zsl_real_t s,
zsl_real_t *dd);
Expand All @@ -96,10 +97,10 @@ int zsl_comp_dms_to_dd(zsl_real_t d, zsl_real_t m, zsl_real_t s,
* Source:
* https://cdn-shop.adafruit.com/datasheets/AN203_Compass_Heading_Using_Magnetometers.pdf
*
* @param m Input corrected magnetometer tridimensional vector, in micro
* @param m Input corrected magnetometer tridimensional vector, in micro
* Tesla.
* @param d Output angle between the magnetic north and the x axis, in
* degrees.
* @param d Output angle between the magnetic north and the x axis, in
* degrees.
*
* @return 0 if everything executed normally, or a negative error code if the
* dimension of the magnetometer vector is not three.
Expand Down Expand Up @@ -130,13 +131,13 @@ int zsl_comp_magn_north(struct zsl_vec *m, zsl_real_t *d);
* upwards, and that the input magnetometer data has already been corrected
* for hard and soft iron errors.
*
* @param m Input magnetometer tridimensional vector, in micro Tesla.
* @param dec Input magnetic declination, in degrees.
* @param m Input magnetometer tridimensional vector, in micro Tesla.
* @param dec Input magnetic declination, in degrees.
* @param b Output angle deviation between true or geographic north and
* the x axis, in degrees (AKA true bearing).
*
* @return 0 if everything executed normally, or a negative error code if the
* dimension of the magnetometer vector is not three.
* dimension of the magnetometer vector is not three.
*/
int zsl_comp_geo_north(struct zsl_vec *m, zsl_real_t dec, zsl_real_t *b);

Expand Down
6 changes: 3 additions & 3 deletions include/zsl/orientation/euler.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,16 +57,16 @@ struct zsl_euler {
* same memory address to a @ref zsl_vec, allowing for vector functions
* to be used on the zsl_euler XYZ values.
*
* @param e Pointer to the zsl_euler struct to use.
* @param v Pointer to the zsl_vec struct to use.
* @param e Pointer to the zsl_euler struct to use.
* @param v Pointer to the zsl_vec struct to use.
*
* @return 0 if everything executed correctly, otherwise a negative error code.
*/
int zsl_eul_to_vec(struct zsl_euler *e, struct zsl_vec *v);

/**
* @brief Print the supplied euler angles vector using printf in a
* human-readable manner.
* human-readable manner.
*
* @param e Pointer to the vector containing the euler angles to print.
*
Expand Down
32 changes: 17 additions & 15 deletions include/zsl/orientation/fusion/aqua.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@
* @brief AQUA sensor fuion algorithm.
*
* @ingroup FUSION_ALGORITHMS
* @{ */
* @{
*/

/**
* @file
Expand Down Expand Up @@ -40,32 +41,33 @@ extern "C" {
*/
struct zsl_fus_aqua_cfg {
/**
* @brief A value between 0.0 and 1.0 which sets the gain for the cut-off
* frequency of the filter. Adjust this value to control LERP or
* SLERP, which reduces the amount of high frequency noise in the
* accelerometer. Alpha must be calculated in static conditions.
* @brief A value between 0.0 and 1.0 which sets the gain for the
* cut-off frequency of the filter. Adjust this value to control
* LERP or SLERP, which reduces the amount of high frequency
* noise in the accelerometer. Alpha must be calculated in
* static conditions.
*/
zsl_real_t alpha;

/**
* @brief Similar to alpha, this variable is set between 0.0 and 1.0 and is
* used to control the LERP or SLERP, which reduces the amount of
* high frequency noise in the magnetometer. Beta must be calculated
* in static conditions.
* @brief Similar to alpha, this variable is set between 0.0 and 1.0
* and is used to control the LERP or SLERP, which reduces the
* amount of high frequency noise in the magnetometer. Beta
* must be calculated in static conditions.
*/
zsl_real_t beta;

/**
* @brief Threshold value to determine whether to compute LERP or SLERP
* to reduce the amount of high frequency noise of the accelerometer
* in the Dq_acc vector. Typically set to 0.9.
* @brief Threshold value to determine whether to compute LERP or
* SLERP to reduce the amount of high frequency noise of the
* accelerometer in the Dq_acc vector. Typically set to 0.9.
*/
zsl_real_t e_a;

/**
* @brief Threshold value to determine whether to compute LERP or SLERP
* to reduce the amount of high frequency noise of the magnetometer
* in the Dq_mag vector. Typically set to 0.9.
* @brief Threshold value to determine whether to compute LERP or
* SLERP to reduce the amount of high frequency noise of the
* magnetometer in the Dq_mag vector. Typically set to 0.9.
*/
zsl_real_t e_m;
};
Expand Down
Loading

0 comments on commit 3a1bf08

Please sign in to comment.