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. 17
      libraries/AP_Math/AP_GeodesicGrid.cpp
  2. 16
      libraries/AP_Math/AP_GeodesicGrid.h
  3. 50
      libraries/AP_Math/tests/test_geodesic_grid.cpp

17
libraries/AP_Math/AP_GeodesicGrid.cpp

@ -184,8 +184,7 @@ const Matrix3f AP_GeodesicGrid::_mid_inverses[10]{ @@ -184,8 +184,7 @@ const Matrix3f AP_GeodesicGrid::_mid_inverses[10]{
{ 0.618034f, 0.000000f, -1.000000f}},
};
int AP_GeodesicGrid::section(const Vector3f& v,
const bool inclusive)
int AP_GeodesicGrid::section(const Vector3f &v, bool inclusive)
{
int i = _triangle_index(v, inclusive);
if (i < 0) {
@ -200,8 +199,7 @@ int AP_GeodesicGrid::section(const Vector3f& v, @@ -200,8 +199,7 @@ int AP_GeodesicGrid::section(const Vector3f& v,
return 4 * i + j;
}
int AP_GeodesicGrid::_neighbor_umbrella_component(int idx,
int comp_idx)
int AP_GeodesicGrid::_neighbor_umbrella_component(int idx, int comp_idx)
{
if (idx < 3) {
return _neighbor_umbrellas[idx].components[comp_idx];
@ -210,8 +208,8 @@ int AP_GeodesicGrid::_neighbor_umbrella_component(int idx, @@ -210,8 +208,8 @@ int AP_GeodesicGrid::_neighbor_umbrella_component(int idx,
}
int AP_GeodesicGrid::_from_neighbor_umbrella(int idx,
const Vector3f& v,
const Vector3f& u,
const Vector3f &v,
const Vector3f &u,
bool inclusive)
{
/* The following comparisons between the umbrella's first and second
@ -306,8 +304,7 @@ int AP_GeodesicGrid::_from_neighbor_umbrella(int idx, @@ -306,8 +304,7 @@ int AP_GeodesicGrid::_from_neighbor_umbrella(int idx,
}
}
int AP_GeodesicGrid::_triangle_index(const Vector3f& v,
const bool inclusive)
int AP_GeodesicGrid::_triangle_index(const Vector3f &v, bool inclusive)
{
/* w holds the coordinates of v with respect to the basis comprised by the
* vectors of T_i */
@ -441,8 +438,8 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f& v, @@ -441,8 +438,8 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f& v,
}
int AP_GeodesicGrid::_subtriangle_index(const unsigned int triangle_index,
const Vector3f& v,
const bool inclusive)
const Vector3f &v,
bool inclusive)
{
/* 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 */

16
libraries/AP_Math/AP_GeodesicGrid.h

@ -123,7 +123,7 @@ public: @@ -123,7 +123,7 @@ public:
* the null vector or the section isn't found, which might happen when \p
* inclusive is false.
*/
static int section(const Vector3f& v, const bool inclusive = false);
static int section(const Vector3f &v, bool inclusive = false);
private:
/*
@ -235,8 +235,8 @@ private: @@ -235,8 +235,8 @@ private:
*
* @return The icosahedron triangle's index of the component.
*/
static int _neighbor_umbrella_component(int umbrella_index,
int component_index);
static int _neighbor_umbrella_component(int umbrella_index, int component_idx);
/**
* Find the icosahedron triangle index of the component of
* #_neighbor_umbrellas[umbrella_index] that is crossed by \p v.
@ -257,8 +257,8 @@ private: @@ -257,8 +257,8 @@ private:
* happen when \p inclusive is false.
*/
static int _from_neighbor_umbrella(int umbrella_index,
const Vector3f& v,
const Vector3f& u,
const Vector3f &v,
const Vector3f &u,
bool inclusive);
/**
@ -272,7 +272,7 @@ private: @@ -272,7 +272,7 @@ private:
* @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.
*/
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
@ -293,6 +293,6 @@ private: @@ -293,6 +293,6 @@ private:
* triangle isn't found, which might happen when \p inclusive is false.
*/
static int _subtriangle_index(const unsigned int triangle_index,
const Vector3f& v,
const bool inclusive);
const Vector3f &v,
bool inclusive);
};

50
libraries/AP_Math/tests/test_geodesic_grid.cpp

@ -47,7 +47,7 @@ protected: @@ -47,7 +47,7 @@ protected:
*
* @param p[in] The test parameter.
*/
void test_triangles_indexes(const TestParam& p) {
void test_triangles_indexes(const TestParam &p) {
if (p.section >= 0) {
int expected_triangle =
p.section / AP_GeodesicGrid::NUM_SUBTRIANGLES;
@ -96,39 +96,39 @@ static const Vector3f triangles[20][3] = { @@ -96,39 +96,39 @@ static const Vector3f triangles[20][3] = {
};
static bool section_triangle(unsigned int section_index,
Vector3f& a,
Vector3f& b,
Vector3f& c) {
Vector3f &a,
Vector3f &b,
Vector3f &c) {
if (section_index >= 80) {
return false;
}
unsigned int i = section_index / 4;
unsigned int j = section_index % 4;
auto& t = triangles[i];
auto &t = triangles[i];
Vector3f mt[3]{(t[0] + t[1]) / 2, (t[1] + t[2]) / 2, (t[2] + t[0]) / 2};
switch (j) {
case 0:
a = mt[0];
b = mt[1];
c = mt[2];
break;
case 1:
a = t[0];
b = mt[0];
c = mt[2];
break;
case 2:
a = mt[0];
b = t[1];
c = mt[1];
break;
case 3:
a = mt[2];
b = mt[1];
c = t[2];
break;
case 0:
a = mt[0];
b = mt[1];
c = mt[2];
break;
case 1:
a = t[0];
b = mt[0];
c = mt[2];
break;
case 2:
a = mt[0];
b = t[1];
c = mt[1];
break;
case 3:
a = mt[2];
b = mt[1];
c = t[2];
break;
}
return true;

Loading…
Cancel
Save