13 changed files with 462 additions and 11 deletions
@ -0,0 +1,130 @@
@@ -0,0 +1,130 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file Limits.cpp |
||||
* |
||||
* Limiting / constrain helper functions |
||||
*/ |
||||
|
||||
|
||||
#include <math.h> |
||||
|
||||
#include "Limits.hpp" |
||||
|
||||
|
||||
namespace math { |
||||
|
||||
|
||||
float __EXPORT min(float val1, float val2) |
||||
{ |
||||
return (val1 < val2) ? val1 : val2; |
||||
} |
||||
|
||||
int __EXPORT min(int val1, int val2) |
||||
{ |
||||
return (val1 < val2) ? val1 : val2; |
||||
} |
||||
|
||||
unsigned __EXPORT min(unsigned val1, unsigned val2) |
||||
{ |
||||
return (val1 < val2) ? val1 : val2; |
||||
} |
||||
|
||||
double __EXPORT min(double val1, double val2) |
||||
{ |
||||
return (val1 < val2) ? val1 : val2; |
||||
} |
||||
|
||||
float __EXPORT max(float val1, float val2) |
||||
{ |
||||
return (val1 > val2) ? val1 : val2; |
||||
} |
||||
|
||||
int __EXPORT max(int val1, int val2) |
||||
{ |
||||
return (val1 > val2) ? val1 : val2; |
||||
} |
||||
|
||||
unsigned __EXPORT max(unsigned val1, unsigned val2) |
||||
{ |
||||
return (val1 > val2) ? val1 : val2; |
||||
} |
||||
|
||||
double __EXPORT max(double val1, double val2) |
||||
{ |
||||
return (val1 > val2) ? val1 : val2; |
||||
} |
||||
|
||||
|
||||
float __EXPORT constrain(float val, float min, float max) |
||||
{ |
||||
return (val < min) ? min : ((val > max) ? max : val); |
||||
} |
||||
|
||||
int __EXPORT constrain(int val, int min, int max) |
||||
{ |
||||
return (val < min) ? min : ((val > max) ? max : val); |
||||
} |
||||
|
||||
unsigned __EXPORT constrain(unsigned val, unsigned min, unsigned max) |
||||
{ |
||||
return (val < min) ? min : ((val > max) ? max : val); |
||||
} |
||||
|
||||
double __EXPORT constrain(double val, double min, double max) |
||||
{ |
||||
return (val < min) ? min : ((val > max) ? max : val); |
||||
} |
||||
|
||||
float __EXPORT radians(float degrees) |
||||
{ |
||||
return (degrees / 180.0f) * M_PI_F; |
||||
} |
||||
|
||||
double __EXPORT radians(double degrees) |
||||
{ |
||||
return (degrees / 180.0) * M_PI; |
||||
} |
||||
|
||||
float __EXPORT degrees(float radians) |
||||
{ |
||||
return (radians / M_PI_F) * 180.0f; |
||||
} |
||||
|
||||
double __EXPORT degrees(double radians) |
||||
{ |
||||
return (radians / M_PI) * 180.0; |
||||
} |
||||
|
||||
} |
@ -0,0 +1,80 @@
@@ -0,0 +1,80 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file Limits.hpp |
||||
* |
||||
* Limiting / constrain helper functions |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
namespace math { |
||||
|
||||
|
||||
float __EXPORT min(float val1, float val2); |
||||
|
||||
int __EXPORT min(int val1, int val2); |
||||
|
||||
unsigned __EXPORT min(unsigned val1, unsigned val2); |
||||
|
||||
double __EXPORT min(double val1, double val2); |
||||
|
||||
float __EXPORT max(float val1, float val2); |
||||
|
||||
int __EXPORT max(int val1, int val2); |
||||
|
||||
unsigned __EXPORT max(unsigned val1, unsigned val2); |
||||
|
||||
double __EXPORT max(double val1, double val2); |
||||
|
||||
|
||||
float __EXPORT constrain(float val, float min, float max); |
||||
|
||||
int __EXPORT constrain(int val, int min, int max); |
||||
|
||||
unsigned __EXPORT constrain(unsigned val, unsigned min, unsigned max); |
||||
|
||||
double __EXPORT constrain(double val, double min, double max); |
||||
|
||||
float __EXPORT radians(float degrees); |
||||
|
||||
double __EXPORT radians(double degrees); |
||||
|
||||
float __EXPORT degrees(float radians); |
||||
|
||||
double __EXPORT degrees(double radians); |
||||
|
||||
} |
@ -0,0 +1,103 @@
@@ -0,0 +1,103 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file Vector2f.cpp |
||||
* |
||||
* math vector |
||||
*/ |
||||
|
||||
#include "test/test.hpp" |
||||
|
||||
#include "Vector2f.hpp" |
||||
|
||||
namespace math |
||||
{ |
||||
|
||||
Vector2f::Vector2f() : |
||||
Vector(2) |
||||
{ |
||||
} |
||||
|
||||
Vector2f::Vector2f(const Vector &right) : |
||||
Vector(right) |
||||
{ |
||||
#ifdef VECTOR_ASSERT |
||||
ASSERT(right.getRows() == 2); |
||||
#endif |
||||
} |
||||
|
||||
Vector2f::Vector2f(float x, float y) : |
||||
Vector(2) |
||||
{ |
||||
setX(x); |
||||
setY(y); |
||||
} |
||||
|
||||
Vector2f::Vector2f(const float *data) : |
||||
Vector(2, data) |
||||
{ |
||||
} |
||||
|
||||
Vector2f::~Vector2f() |
||||
{ |
||||
} |
||||
|
||||
float Vector2f::cross(const Vector2f &b) const |
||||
{ |
||||
const Vector2f &a = *this; |
||||
return a(0)*b(1) - a(1)*b(0); |
||||
} |
||||
|
||||
float Vector2f::operator %(const Vector2f &v) const |
||||
{ |
||||
return cross(v); |
||||
} |
||||
|
||||
float Vector2f::operator *(const Vector2f &v) const |
||||
{ |
||||
return dot(v); |
||||
} |
||||
|
||||
int __EXPORT vector2fTest() |
||||
{ |
||||
printf("Test Vector2f\t\t: "); |
||||
// test float ctor
|
||||
Vector2f v(1, 2); |
||||
ASSERT(equal(v(0), 1)); |
||||
ASSERT(equal(v(1), 2)); |
||||
printf("PASS\n"); |
||||
return 0; |
||||
} |
||||
|
||||
} // namespace math
|
@ -0,0 +1,79 @@
@@ -0,0 +1,79 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file Vector2f.hpp |
||||
* |
||||
* math 3 vector |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include "Vector.hpp" |
||||
|
||||
namespace math |
||||
{ |
||||
|
||||
class __EXPORT Vector2f : |
||||
public Vector |
||||
{ |
||||
public: |
||||
Vector2f(); |
||||
Vector2f(const Vector &right); |
||||
Vector2f(float x, float y); |
||||
Vector2f(const float *data); |
||||
virtual ~Vector2f(); |
||||
float cross(const Vector2f &b) const; |
||||
float operator %(const Vector2f &v) const; |
||||
float operator *(const Vector2f &v) const; |
||||
inline Vector2f operator*(const float &right) const { |
||||
return Vector::operator*(right); |
||||
} |
||||
|
||||
/**
|
||||
* accessors |
||||
*/ |
||||
void setX(float x) { (*this)(0) = x; } |
||||
void setY(float y) { (*this)(1) = y; } |
||||
const float &getX() const { return (*this)(0); } |
||||
const float &getY() const { return (*this)(1); } |
||||
}; |
||||
|
||||
class __EXPORT Vector2 : |
||||
public Vector2f |
||||
{ |
||||
}; |
||||
|
||||
int __EXPORT vector2fTest(); |
||||
} // math
|
||||
|
Loading…
Reference in new issue