Browse Source

AP_Math: fix some coding style mistakes

- fix alignement of &
    - remove const from bool arguments
master
Lucas De Marchi 9 years ago
parent
commit
fa6f2c6b67
  1. 11
      libraries/AP_Math/AP_GeodesicGrid.cpp
  2. 10
      libraries/AP_Math/AP_GeodesicGrid.h

11
libraries/AP_Math/AP_GeodesicGrid.cpp

@ -184,8 +184,7 @@ const Matrix3f AP_GeodesicGrid::_mid_inverses[10]{
{ 0.618034f, 0.000000f, -1.000000f}}, { 0.618034f, 0.000000f, -1.000000f}},
}; };
int AP_GeodesicGrid::section(const Vector3f& v, int AP_GeodesicGrid::section(const Vector3f &v, bool inclusive)
const bool inclusive)
{ {
int i = _triangle_index(v, inclusive); int i = _triangle_index(v, inclusive);
if (i < 0) { if (i < 0) {
@ -200,8 +199,7 @@ int AP_GeodesicGrid::section(const Vector3f& v,
return 4 * i + j; return 4 * i + j;
} }
int AP_GeodesicGrid::_neighbor_umbrella_component(int idx, int AP_GeodesicGrid::_neighbor_umbrella_component(int idx, int comp_idx)
int comp_idx)
{ {
if (idx < 3) { if (idx < 3) {
return _neighbor_umbrellas[idx].components[comp_idx]; return _neighbor_umbrellas[idx].components[comp_idx];
@ -306,8 +304,7 @@ int AP_GeodesicGrid::_from_neighbor_umbrella(int idx,
} }
} }
int AP_GeodesicGrid::_triangle_index(const Vector3f& v, int AP_GeodesicGrid::_triangle_index(const Vector3f &v, bool inclusive)
const bool inclusive)
{ {
/* w holds the coordinates of v with respect to the basis comprised by the /* w holds the coordinates of v with respect to the basis comprised by the
* vectors of T_i */ * vectors of T_i */
@ -442,7 +439,7 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f& v,
int AP_GeodesicGrid::_subtriangle_index(const unsigned int triangle_index, int AP_GeodesicGrid::_subtriangle_index(const unsigned int triangle_index,
const Vector3f &v, const Vector3f &v,
const bool inclusive) bool inclusive)
{ {
/* w holds the coordinates of v with respect to the basis comprised by the /* w holds the coordinates of v with respect to the basis comprised by the
* vectors of the middle triangle of T_i where i is triangle_index */ * vectors of the middle triangle of T_i where i is triangle_index */

10
libraries/AP_Math/AP_GeodesicGrid.h

@ -123,7 +123,7 @@ public:
* the null vector or the section isn't found, which might happen when \p * the null vector or the section isn't found, which might happen when \p
* inclusive is false. * inclusive is false.
*/ */
static int section(const Vector3f& v, const bool inclusive = false); static int section(const Vector3f &v, bool inclusive = false);
private: private:
/* /*
@ -235,8 +235,8 @@ private:
* *
* @return The icosahedron triangle's index of the component. * @return The icosahedron triangle's index of the component.
*/ */
static int _neighbor_umbrella_component(int umbrella_index, static int _neighbor_umbrella_component(int umbrella_index, int component_idx);
int component_index);
/** /**
* Find the icosahedron triangle index of the component of * Find the icosahedron triangle index of the component of
* #_neighbor_umbrellas[umbrella_index] that is crossed by \p v. * #_neighbor_umbrellas[umbrella_index] that is crossed by \p v.
@ -272,7 +272,7 @@ private:
* @return The index of the triangle. The value -1 is returned if the * @return The index of the triangle. The value -1 is returned if the
* triangle isn't found, which might happen when \p inclusive is false. * triangle isn't found, which might happen when \p inclusive is false.
*/ */
static int _triangle_index(const Vector3f& v, const bool inclusive); static int _triangle_index(const Vector3f &v, bool inclusive);
/** /**
* Find which sub-triangle of the icosahedron's triangle pointed by \p * Find which sub-triangle of the icosahedron's triangle pointed by \p
@ -294,5 +294,5 @@ private:
*/ */
static int _subtriangle_index(const unsigned int triangle_index, static int _subtriangle_index(const unsigned int triangle_index,
const Vector3f &v, const Vector3f &v,
const bool inclusive); bool inclusive);
}; };

Loading…
Cancel
Save