Merge commit 'a6a91798b24552522373414d43981b082025cfdd' into ControlCore
This commit is contained in:
commit
8ce608ae2a
@ -5,16 +5,18 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
DigitalInput::DigitalInput(Participant* participant, unsigned char pin) : TouchSensor(participant) {
|
DigitalInput::DigitalInput(Participant* participant, unsigned char pin)
|
||||||
this->pin = pin;
|
: TouchSensor(participant) {
|
||||||
|
this->pin = pin;
|
||||||
|
|
||||||
pinMode(pin, INPUT);
|
pinMode(pin, INPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
void DigitalInput::Update(unsigned long currentTimeMs) {
|
void DigitalInput::Update(unsigned long currentTimeMs, bool recursive) {
|
||||||
this->touchedSomething = digitalRead(pin) == LOW;
|
this->touchedSomething = digitalRead(pin) == LOW;
|
||||||
|
// std::cout << "DigitalINput pin " << (int)this->pin << ": " <<
|
||||||
// std::cout << "DigitalINput pin " << (int)this->pin << ": " << this->touchedSomething << "\n";
|
// this->touchedSomething << "\n";
|
||||||
|
Thing::Update(currentTimeMs, recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
} // namespace Arduino
|
} // namespace Arduino
|
||||||
|
@ -13,8 +13,9 @@ class DigitalInput : public TouchSensor {
|
|||||||
/// @param pin The digital pin
|
/// @param pin The digital pin
|
||||||
DigitalInput(Participant* participant, unsigned char pin);
|
DigitalInput(Participant* participant, unsigned char pin);
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
||||||
virtual void Update(unsigned long currentTimeMs) override;
|
virtual void Update(unsigned long currentTimeMs,
|
||||||
|
bool recursive = false) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief The pin used for digital input
|
/// @brief The pin used for digital input
|
||||||
|
@ -5,7 +5,9 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
namespace Arduino {
|
namespace Arduino {
|
||||||
|
|
||||||
UltrasonicSensor::UltrasonicSensor(Participant* participant, unsigned char pinTrigger, unsigned char pinEcho)
|
UltrasonicSensor::UltrasonicSensor(Participant* participant,
|
||||||
|
unsigned char pinTrigger,
|
||||||
|
unsigned char pinEcho)
|
||||||
: TouchSensor(participant) {
|
: TouchSensor(participant) {
|
||||||
this->pinTrigger = pinTrigger;
|
this->pinTrigger = pinTrigger;
|
||||||
this->pinEcho = pinEcho;
|
this->pinEcho = pinEcho;
|
||||||
@ -23,7 +25,8 @@ float UltrasonicSensor::GetDistance() {
|
|||||||
digitalWrite(pinTrigger, LOW);
|
digitalWrite(pinTrigger, LOW);
|
||||||
|
|
||||||
// Measure the duration of the pulse on the echo pin
|
// Measure the duration of the pulse on the echo pin
|
||||||
float duration_us = pulseIn(pinEcho, HIGH, 100000); // the result is in microseconds
|
float duration_us =
|
||||||
|
pulseIn(pinEcho, HIGH, 100000); // the result is in microseconds
|
||||||
|
|
||||||
// Calculate the distance:
|
// Calculate the distance:
|
||||||
// * Duration should be divided by 2, because the ping goes to the object
|
// * Duration should be divided by 2, because the ping goes to the object
|
||||||
@ -43,14 +46,16 @@ float UltrasonicSensor::GetDistance() {
|
|||||||
|
|
||||||
this->touchedSomething |= (this->distance <= this->touchDistance);
|
this->touchedSomething |= (this->distance <= this->touchDistance);
|
||||||
|
|
||||||
// std::cout << "Ultrasonic " << this->distance << " " << this->touchedSomething << "\n";
|
// std::cout << "Ultrasonic " << this->distance << " " <<
|
||||||
|
// this->touchedSomething << "\n";
|
||||||
|
|
||||||
return distance;
|
return distance;
|
||||||
}
|
}
|
||||||
|
|
||||||
void UltrasonicSensor::Update(unsigned long currentTimeMs) {
|
void UltrasonicSensor::Update(unsigned long currentTimeMs, bool recursive) {
|
||||||
this->touchedSomething = false;
|
this->touchedSomething = false;
|
||||||
GetDistance();
|
GetDistance();
|
||||||
|
Thing::Update(currentTimeMs, recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
// void UltrasonicSensor::ProcessBinary(char* bytes) {
|
// void UltrasonicSensor::ProcessBinary(char* bytes) {
|
||||||
|
@ -12,7 +12,9 @@ class UltrasonicSensor : public TouchSensor {
|
|||||||
/// @param participant The participant to use
|
/// @param participant The participant to use
|
||||||
/// @param pinTrigger The pin number of the trigger signal
|
/// @param pinTrigger The pin number of the trigger signal
|
||||||
/// @param pinEcho The pin number of the echo signal
|
/// @param pinEcho The pin number of the echo signal
|
||||||
UltrasonicSensor(Participant* participant, unsigned char pinTrigger, unsigned char pinEcho);
|
UltrasonicSensor(Participant* participant,
|
||||||
|
unsigned char pinTrigger,
|
||||||
|
unsigned char pinEcho);
|
||||||
|
|
||||||
// parameters
|
// parameters
|
||||||
|
|
||||||
@ -23,12 +25,14 @@ class UltrasonicSensor : public TouchSensor {
|
|||||||
|
|
||||||
/// @brief The last read distance
|
/// @brief The last read distance
|
||||||
float distance = 0;
|
float distance = 0;
|
||||||
/// @brief erform an ultrasonic 'ping' to determine the distance to the nearest object
|
/// @brief erform an ultrasonic 'ping' to determine the distance to the
|
||||||
|
/// nearest object
|
||||||
/// @return the measured distance in meters to the nearest object
|
/// @return the measured distance in meters to the nearest object
|
||||||
float GetDistance();
|
float GetDistance();
|
||||||
|
|
||||||
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
/// @copydoc RoboidControl::Thing::Update(unsigned long currentTimeMs)
|
||||||
virtual void Update(unsigned long currentTimeMs) override;
|
virtual void Update(unsigned long currentTimeMs,
|
||||||
|
bool recursive = false) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief The pin number of the trigger signal
|
/// @brief The pin number of the trigger signal
|
||||||
|
@ -5,8 +5,9 @@ if(ESP_PLATFORM)
|
|||||||
INCLUDE_DIRS "."
|
INCLUDE_DIRS "."
|
||||||
)
|
)
|
||||||
else()
|
else()
|
||||||
project(RoboidCOntrol)
|
project(RoboidControl)
|
||||||
add_subdirectory(LinearAlgebra)
|
add_subdirectory(LinearAlgebra)
|
||||||
|
add_subdirectory(Examples)
|
||||||
|
|
||||||
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
set(CMAKE_CXX_STANDARD 17) # Enable c++11 standard
|
||||||
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
|
||||||
@ -51,13 +52,6 @@ else()
|
|||||||
LinearAlgebra
|
LinearAlgebra
|
||||||
)
|
)
|
||||||
|
|
||||||
# if(MSVC)
|
|
||||||
# target_compile_options(RoboidControlTest PRIVATE /W4 /WX)
|
|
||||||
# # else()
|
|
||||||
# # target_compile_options(RoboidControlTest PRIVATE -Wall -Wextra -Wpedantic -Werror)
|
|
||||||
# endif()
|
|
||||||
|
|
||||||
|
|
||||||
include(GoogleTest)
|
include(GoogleTest)
|
||||||
gtest_discover_tests(RoboidControlTest)
|
gtest_discover_tests(RoboidControlTest)
|
||||||
endif()
|
endif()
|
||||||
|
50
Examples/BB2B.cpp
Normal file
50
Examples/BB2B.cpp
Normal file
@ -0,0 +1,50 @@
|
|||||||
|
#include "Thing.h"
|
||||||
|
#include "Things/DifferentialDrive.h"
|
||||||
|
#include "Things/TouchSensor.h"
|
||||||
|
|
||||||
|
#if defined(ARDUINO)
|
||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
|
#else
|
||||||
|
#include <chrono>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
using namespace std::this_thread;
|
||||||
|
using namespace std::chrono;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
using namespace RoboidControl;
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
// The robot's propulsion is a differential drive
|
||||||
|
DifferentialDrive* bb2b = new DifferentialDrive();
|
||||||
|
// Is has a touch sensor at the front left of the roboid
|
||||||
|
TouchSensor* touchLeft = new TouchSensor(bb2b);
|
||||||
|
// and other one on the right
|
||||||
|
TouchSensor* touchRight = new TouchSensor(bb2b);
|
||||||
|
|
||||||
|
// Do forever:
|
||||||
|
while (true) {
|
||||||
|
// The left wheel turns forward when nothing is touched on the right side
|
||||||
|
// and turn backward when the roboid hits something on the right
|
||||||
|
float leftWheelSpeed = (touchRight->touchedSomething) ? -600.0f : 600.0f;
|
||||||
|
// The right wheel does the same, but instead is controlled by
|
||||||
|
// touches on the left side
|
||||||
|
float rightWheelSpeed = (touchLeft->touchedSomething) ? -600.0f : 600.0f;
|
||||||
|
// When both sides are touching something, both wheels will turn backward
|
||||||
|
// and the roboid will move backwards
|
||||||
|
bb2b->SetWheelVelocity(leftWheelSpeed, rightWheelSpeed);
|
||||||
|
|
||||||
|
// Update the roboid state
|
||||||
|
bb2b->Update(true);
|
||||||
|
|
||||||
|
// and sleep for 100ms
|
||||||
|
#if defined(ARDUINO)
|
||||||
|
delay(100);
|
||||||
|
#else
|
||||||
|
sleep_for(milliseconds(100));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
25
Examples/CMakeLists.txt
Normal file
25
Examples/CMakeLists.txt
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
# examples/CMakeLists.txt
|
||||||
|
|
||||||
|
# Specify the minimum CMake version
|
||||||
|
cmake_minimum_required(VERSION 3.10)
|
||||||
|
|
||||||
|
# Specify the path to the main project directory
|
||||||
|
set(MAIN_PROJECT_DIR "${CMAKE_SOURCE_DIR}/..")
|
||||||
|
|
||||||
|
# Set the project name
|
||||||
|
project(Examples)
|
||||||
|
|
||||||
|
include_directories(..)
|
||||||
|
|
||||||
|
# Add the executable for the main project
|
||||||
|
#add_executable(MainExecutable ${SOURCES})
|
||||||
|
# Find the main project library (assuming it's defined in the root CMakeLists.txt)
|
||||||
|
#find_package(RoboidControl REQUIRED) # Replace MyLibrary with your actual library name
|
||||||
|
|
||||||
|
# Add example executables
|
||||||
|
add_executable(BB2B BB2B.cpp)
|
||||||
|
target_link_libraries(
|
||||||
|
BB2B
|
||||||
|
RoboidControl
|
||||||
|
LinearAlgebra
|
||||||
|
)
|
@ -3,15 +3,15 @@
|
|||||||
// file, You can obtain one at https ://mozilla.org/MPL/2.0/.
|
// file, You can obtain one at https ://mozilla.org/MPL/2.0/.
|
||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
#include "FloatSingle.h"
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include "FloatSingle.h"
|
||||||
|
|
||||||
const float Rad2Deg = 57.29578F;
|
namespace LinearAlgebra {
|
||||||
const float Deg2Rad = 0.0174532924F;
|
|
||||||
|
|
||||||
//===== AngleSingle, AngleOf<float>
|
//===== AngleSingle, AngleOf<float>
|
||||||
|
|
||||||
template <> AngleOf<float> Passer::LinearAlgebra::AngleOf<float>::Degrees(float degrees) {
|
template <>
|
||||||
|
AngleOf<float> AngleOf<float>::Degrees(float degrees) {
|
||||||
if (isfinite(degrees)) {
|
if (isfinite(degrees)) {
|
||||||
while (degrees < -180)
|
while (degrees < -180)
|
||||||
degrees += 360;
|
degrees += 360;
|
||||||
@ -22,7 +22,8 @@ template <> AngleOf<float> Passer::LinearAlgebra::AngleOf<float>::Degrees(float
|
|||||||
return AngleOf<float>(degrees);
|
return AngleOf<float>(degrees);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> AngleOf<float> AngleOf<float>::Radians(float radians) {
|
template <>
|
||||||
|
AngleOf<float> AngleOf<float>::Radians(float radians) {
|
||||||
if (isfinite(radians)) {
|
if (isfinite(radians)) {
|
||||||
while (radians <= -pi)
|
while (radians <= -pi)
|
||||||
radians += 2 * pi;
|
radians += 2 * pi;
|
||||||
@ -33,9 +34,13 @@ template <> AngleOf<float> AngleOf<float>::Radians(float radians) {
|
|||||||
return Binary(radians * Rad2Deg);
|
return Binary(radians * Rad2Deg);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> float AngleOf<float>::InDegrees() const { return this->value; }
|
template <>
|
||||||
|
float AngleOf<float>::InDegrees() const {
|
||||||
|
return this->value;
|
||||||
|
}
|
||||||
|
|
||||||
template <> float AngleOf<float>::InRadians() const {
|
template <>
|
||||||
|
float AngleOf<float>::InRadians() const {
|
||||||
return this->value * Deg2Rad;
|
return this->value * Deg2Rad;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -58,25 +63,29 @@ AngleOf<signed short> AngleOf<signed short>::Radians(float radians) {
|
|||||||
return Binary(value);
|
return Binary(value);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> float AngleOf<signed short>::InDegrees() const {
|
template <>
|
||||||
|
float AngleOf<signed short>::InDegrees() const {
|
||||||
float degrees = this->value / 65536.0f * 360.0f;
|
float degrees = this->value / 65536.0f * 360.0f;
|
||||||
return degrees;
|
return degrees;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> float AngleOf<signed short>::InRadians() const {
|
template <>
|
||||||
|
float AngleOf<signed short>::InRadians() const {
|
||||||
float radians = this->value / 65536.0f * (2 * pi);
|
float radians = this->value / 65536.0f * (2 * pi);
|
||||||
return radians;
|
return radians;
|
||||||
}
|
}
|
||||||
|
|
||||||
//===== Angle8, AngleOf<signed char>
|
//===== Angle8, AngleOf<signed char>
|
||||||
|
|
||||||
template <> AngleOf<signed char> AngleOf<signed char>::Degrees(float degrees) {
|
template <>
|
||||||
|
AngleOf<signed char> AngleOf<signed char>::Degrees(float degrees) {
|
||||||
// map float [-180..180) to integer [-128..127)
|
// map float [-180..180) to integer [-128..127)
|
||||||
signed char value = (signed char)roundf(degrees / 360.0F * 256.0F);
|
signed char value = (signed char)roundf(degrees / 360.0F * 256.0F);
|
||||||
return Binary(value);
|
return Binary(value);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> AngleOf<signed char> AngleOf<signed char>::Radians(float radians) {
|
template <>
|
||||||
|
AngleOf<signed char> AngleOf<signed char>::Radians(float radians) {
|
||||||
if (!isfinite(radians))
|
if (!isfinite(radians))
|
||||||
return AngleOf<signed char>::zero;
|
return AngleOf<signed char>::zero;
|
||||||
|
|
||||||
@ -85,32 +94,42 @@ template <> AngleOf<signed char> AngleOf<signed char>::Radians(float radians) {
|
|||||||
return Binary(value);
|
return Binary(value);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> float AngleOf<signed char>::InDegrees() const {
|
template <>
|
||||||
|
float AngleOf<signed char>::InDegrees() const {
|
||||||
float degrees = this->value / 256.0f * 360.0f;
|
float degrees = this->value / 256.0f * 360.0f;
|
||||||
return degrees;
|
return degrees;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <> float AngleOf<signed char>::InRadians() const {
|
template <>
|
||||||
|
float AngleOf<signed char>::InRadians() const {
|
||||||
float radians = this->value / 128.0f * pi;
|
float radians = this->value / 128.0f * pi;
|
||||||
return radians;
|
return radians;
|
||||||
}
|
}
|
||||||
|
|
||||||
//===== Generic
|
//===== Generic
|
||||||
|
|
||||||
template <typename T> AngleOf<T>::AngleOf() : value(0) {}
|
template <typename T>
|
||||||
|
AngleOf<T>::AngleOf() : value(0) {}
|
||||||
|
|
||||||
template <typename T> AngleOf<T>::AngleOf(T rawValue) : value(rawValue) {}
|
template <typename T>
|
||||||
|
AngleOf<T>::AngleOf(T rawValue) : value(rawValue) {}
|
||||||
|
|
||||||
template <typename T> const AngleOf<T> AngleOf<T>::zero = AngleOf<T>();
|
template <typename T>
|
||||||
|
const AngleOf<T> AngleOf<T>::zero = AngleOf<T>();
|
||||||
|
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::Binary(T rawValue) {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::Binary(T rawValue) {
|
||||||
AngleOf<T> angle = AngleOf<T>();
|
AngleOf<T> angle = AngleOf<T>();
|
||||||
angle.SetBinary(rawValue);
|
angle.SetBinary(rawValue);
|
||||||
return angle;
|
return angle;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> T AngleOf<T>::GetBinary() const { return this->value; }
|
template <typename T>
|
||||||
template <typename T> void AngleOf<T>::SetBinary(T rawValue) {
|
T AngleOf<T>::GetBinary() const {
|
||||||
|
return this->value;
|
||||||
|
}
|
||||||
|
template <typename T>
|
||||||
|
void AngleOf<T>::SetBinary(T rawValue) {
|
||||||
this->value = rawValue;
|
this->value = rawValue;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -119,24 +138,28 @@ bool AngleOf<T>::operator==(const AngleOf<T> angle) const {
|
|||||||
return this->value == angle.value;
|
return this->value == angle.value;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> bool AngleOf<T>::operator>(AngleOf<T> angle) const {
|
template <typename T>
|
||||||
|
bool AngleOf<T>::operator>(AngleOf<T> angle) const {
|
||||||
return this->value > angle.value;
|
return this->value > angle.value;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> bool AngleOf<T>::operator>=(AngleOf<T> angle) const {
|
template <typename T>
|
||||||
|
bool AngleOf<T>::operator>=(AngleOf<T> angle) const {
|
||||||
return this->value >= angle.value;
|
return this->value >= angle.value;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> bool AngleOf<T>::operator<(AngleOf<T> angle) const {
|
template <typename T>
|
||||||
|
bool AngleOf<T>::operator<(AngleOf<T> angle) const {
|
||||||
return this->value < angle.value;
|
return this->value < angle.value;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> bool AngleOf<T>::operator<=(AngleOf<T> angle) const {
|
template <typename T>
|
||||||
|
bool AngleOf<T>::operator<=(AngleOf<T> angle) const {
|
||||||
return this->value <= angle.value;
|
return this->value <= angle.value;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
signed int Passer::LinearAlgebra::AngleOf<T>::Sign(AngleOf<T> angle) {
|
signed int AngleOf<T>::Sign(AngleOf<T> angle) {
|
||||||
if (angle.value < 0)
|
if (angle.value < 0)
|
||||||
return -1;
|
return -1;
|
||||||
if (angle.value > 0)
|
if (angle.value > 0)
|
||||||
@ -145,51 +168,52 @@ signed int Passer::LinearAlgebra::AngleOf<T>::Sign(AngleOf<T> angle) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> Passer::LinearAlgebra::AngleOf<T>::Abs(AngleOf<T> angle) {
|
AngleOf<T> AngleOf<T>::Abs(AngleOf<T> angle) {
|
||||||
if (Sign(angle) < 0)
|
if (Sign(angle) < 0)
|
||||||
return -angle;
|
return -angle;
|
||||||
else
|
else
|
||||||
return angle;
|
return angle;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::operator-() const {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::operator-() const {
|
||||||
AngleOf<T> angle = Binary(-this->value);
|
AngleOf<T> angle = Binary(-this->value);
|
||||||
return angle;
|
return angle;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <>
|
template <>
|
||||||
AngleOf<float> AngleOf<float>::operator-(const AngleOf<float> &angle) const {
|
AngleOf<float> AngleOf<float>::operator-(const AngleOf<float>& angle) const {
|
||||||
AngleOf<float> r = Binary(this->value - angle.value);
|
AngleOf<float> r = Binary(this->value - angle.value);
|
||||||
r = Normalize(r);
|
r = Normalize(r);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> AngleOf<T>::operator-(const AngleOf<T> &angle) const {
|
AngleOf<T> AngleOf<T>::operator-(const AngleOf<T>& angle) const {
|
||||||
AngleOf<T> r = Binary(this->value - angle.value);
|
AngleOf<T> r = Binary(this->value - angle.value);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <>
|
template <>
|
||||||
AngleOf<float> AngleOf<float>::operator+(const AngleOf<float> &angle) const {
|
AngleOf<float> AngleOf<float>::operator+(const AngleOf<float>& angle) const {
|
||||||
AngleOf<float> r = Binary(this->value + angle.value);
|
AngleOf<float> r = Binary(this->value + angle.value);
|
||||||
r = Normalize(r);
|
r = Normalize(r);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> AngleOf<T>::operator+(const AngleOf<T> &angle) const {
|
AngleOf<T> AngleOf<T>::operator+(const AngleOf<T>& angle) const {
|
||||||
AngleOf<T> r = Binary(this->value + angle.value);
|
AngleOf<T> r = Binary(this->value + angle.value);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <>
|
template <>
|
||||||
AngleOf<float> AngleOf<float>::operator+=(const AngleOf<float> &angle) {
|
AngleOf<float> AngleOf<float>::operator+=(const AngleOf<float>& angle) {
|
||||||
this->value += angle.value;
|
this->value += angle.value;
|
||||||
this->Normalize();
|
this->Normalize();
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> AngleOf<T>::operator+=(const AngleOf<T> &angle) {
|
AngleOf<T> AngleOf<T>::operator+=(const AngleOf<T>& angle) {
|
||||||
this->value += angle.value;
|
this->value += angle.value;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
@ -206,7 +230,8 @@ AngleOf<T> AngleOf<T>::operator+=(const AngleOf<T> &angle) {
|
|||||||
// return AngleOf::Degrees((float)factor * angle.InDegrees());
|
// return AngleOf::Degrees((float)factor * angle.InDegrees());
|
||||||
// }
|
// }
|
||||||
|
|
||||||
template <typename T> void AngleOf<T>::Normalize() {
|
template <typename T>
|
||||||
|
void AngleOf<T>::Normalize() {
|
||||||
float angleValue = this->InDegrees();
|
float angleValue = this->InDegrees();
|
||||||
if (!isfinite(angleValue))
|
if (!isfinite(angleValue))
|
||||||
return;
|
return;
|
||||||
@ -218,7 +243,8 @@ template <typename T> void AngleOf<T>::Normalize() {
|
|||||||
*this = AngleOf::Degrees(angleValue);
|
*this = AngleOf::Degrees(angleValue);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::Normalize(AngleOf<T> angle) {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::Normalize(AngleOf<T> angle) {
|
||||||
float angleValue = angle.InDegrees();
|
float angleValue = angle.InDegrees();
|
||||||
if (!isfinite(angleValue))
|
if (!isfinite(angleValue))
|
||||||
return angle;
|
return angle;
|
||||||
@ -237,9 +263,10 @@ AngleOf<T> AngleOf<T>::Clamp(AngleOf<T> angle, AngleOf<T> min, AngleOf<T> max) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> AngleOf<T>::MoveTowards(AngleOf<T> fromAngle, AngleOf<T> toAngle,
|
AngleOf<T> AngleOf<T>::MoveTowards(AngleOf<T> fromAngle,
|
||||||
|
AngleOf<T> toAngle,
|
||||||
float maxDegrees) {
|
float maxDegrees) {
|
||||||
maxDegrees = fmaxf(0, maxDegrees); // filter out negative distances
|
maxDegrees = fmaxf(0, maxDegrees); // filter out negative distances
|
||||||
AngleOf<T> d = toAngle - fromAngle;
|
AngleOf<T> d = toAngle - fromAngle;
|
||||||
float dDegrees = Abs(d).InDegrees();
|
float dDegrees = Abs(d).InDegrees();
|
||||||
d = AngleOf<T>::Degrees(Float::Clamp(dDegrees, 0, maxDegrees));
|
d = AngleOf<T>::Degrees(Float::Clamp(dDegrees, 0, maxDegrees));
|
||||||
@ -249,28 +276,34 @@ AngleOf<T> AngleOf<T>::MoveTowards(AngleOf<T> fromAngle, AngleOf<T> toAngle,
|
|||||||
return fromAngle + d;
|
return fromAngle + d;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> float AngleOf<T>::Cos(AngleOf<T> angle) {
|
template <typename T>
|
||||||
|
float AngleOf<T>::Cos(AngleOf<T> angle) {
|
||||||
return cosf(angle.InRadians());
|
return cosf(angle.InRadians());
|
||||||
}
|
}
|
||||||
template <typename T> float AngleOf<T>::Sin(AngleOf<T> angle) {
|
template <typename T>
|
||||||
|
float AngleOf<T>::Sin(AngleOf<T> angle) {
|
||||||
return sinf(angle.InRadians());
|
return sinf(angle.InRadians());
|
||||||
}
|
}
|
||||||
template <typename T> float AngleOf<T>::Tan(AngleOf<T> angle) {
|
template <typename T>
|
||||||
|
float AngleOf<T>::Tan(AngleOf<T> angle) {
|
||||||
return tanf(angle.InRadians());
|
return tanf(angle.InRadians());
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::Acos(float f) {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::Acos(float f) {
|
||||||
return AngleOf<T>::Radians(acosf(f));
|
return AngleOf<T>::Radians(acosf(f));
|
||||||
}
|
}
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::Asin(float f) {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::Asin(float f) {
|
||||||
return AngleOf<T>::Radians(asinf(f));
|
return AngleOf<T>::Radians(asinf(f));
|
||||||
}
|
}
|
||||||
template <typename T> AngleOf<T> AngleOf<T>::Atan(float f) {
|
template <typename T>
|
||||||
|
AngleOf<T> AngleOf<T>::Atan(float f) {
|
||||||
return AngleOf<T>::Radians(atanf(f));
|
return AngleOf<T>::Radians(atanf(f));
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> Passer::LinearAlgebra::AngleOf<T>::Atan2(float y, float x) {
|
AngleOf<T> AngleOf<T>::Atan2(float y, float x) {
|
||||||
return AngleOf<T>::Radians(atan2f(y, x));
|
return AngleOf<T>::Radians(atan2f(y, x));
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -297,7 +330,7 @@ float AngleOf<T>::CosineRuleSide(float a, float b, AngleOf<T> gamma) {
|
|||||||
float b2 = b * b;
|
float b2 = b * b;
|
||||||
float d =
|
float d =
|
||||||
a2 + b2 -
|
a2 + b2 -
|
||||||
2 * a * b * Cos(gamma); // cosf(gamma * Passer::LinearAlgebra::Deg2Rad);
|
2 * a * b * Cos(gamma); // cosf(gamma * Passer::LinearAlgebra::Deg2Rad);
|
||||||
// Catch edge cases where float inacuracies lead tot nans
|
// Catch edge cases where float inacuracies lead tot nans
|
||||||
if (d < 0)
|
if (d < 0)
|
||||||
return 0;
|
return 0;
|
||||||
@ -354,6 +387,8 @@ AngleOf<T> AngleOf<T>::SineRuleAngle(float a, AngleOf<T> beta, float b) {
|
|||||||
return alpha;
|
return alpha;
|
||||||
}
|
}
|
||||||
|
|
||||||
template class Passer::LinearAlgebra::AngleOf<float>;
|
template class AngleOf<float>;
|
||||||
template class Passer::LinearAlgebra::AngleOf<signed char>;
|
template class AngleOf<signed char>;
|
||||||
template class Passer::LinearAlgebra::AngleOf<signed short>;
|
template class AngleOf<signed short>;
|
||||||
|
|
||||||
|
} // namespace LinearAlgebra
|
@ -5,7 +5,6 @@
|
|||||||
#ifndef ANGLE_H
|
#ifndef ANGLE_H
|
||||||
#define ANGLE_H
|
#define ANGLE_H
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
static float pi = 3.1415927410125732421875F;
|
static float pi = 3.1415927410125732421875F;
|
||||||
@ -18,8 +17,9 @@ static float Deg2Rad = (pi * 2) / 360.0f;
|
|||||||
/// The angle is internally limited to (-180..180] degrees or (-PI...PI]
|
/// The angle is internally limited to (-180..180] degrees or (-PI...PI]
|
||||||
/// radians. When an angle exceeds this range, it is normalized to a value
|
/// radians. When an angle exceeds this range, it is normalized to a value
|
||||||
/// within the range.
|
/// within the range.
|
||||||
template <typename T> class AngleOf {
|
template <typename T>
|
||||||
public:
|
class AngleOf {
|
||||||
|
public:
|
||||||
/// @brief Create a new angle with a zero value
|
/// @brief Create a new angle with a zero value
|
||||||
AngleOf<T>();
|
AngleOf<T>();
|
||||||
|
|
||||||
@ -100,28 +100,28 @@ public:
|
|||||||
/// @brief Substract another angle from this angle
|
/// @brief Substract another angle from this angle
|
||||||
/// @param angle The angle to subtract from this angle
|
/// @param angle The angle to subtract from this angle
|
||||||
/// @return The result of the subtraction
|
/// @return The result of the subtraction
|
||||||
AngleOf<T> operator-(const AngleOf<T> &angle) const;
|
AngleOf<T> operator-(const AngleOf<T>& angle) const;
|
||||||
/// @brief Add another angle from this angle
|
/// @brief Add another angle from this angle
|
||||||
/// @param angle The angle to add to this angle
|
/// @param angle The angle to add to this angle
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
AngleOf<T> operator+(const AngleOf<T> &angle) const;
|
AngleOf<T> operator+(const AngleOf<T>& angle) const;
|
||||||
/// @brief Add another angle to this angle
|
/// @brief Add another angle to this angle
|
||||||
/// @param angle The angle to add to this angle
|
/// @param angle The angle to add to this angle
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
AngleOf<T> operator+=(const AngleOf<T> &angle);
|
AngleOf<T> operator+=(const AngleOf<T>& angle);
|
||||||
|
|
||||||
/// @brief Mutliplies the angle
|
/// @brief Mutliplies the angle
|
||||||
/// @param angle The angle to multiply
|
/// @param angle The angle to multiply
|
||||||
/// @param factor The factor by which the angle is multiplied
|
/// @param factor The factor by which the angle is multiplied
|
||||||
/// @return The multiplied angle
|
/// @return The multiplied angle
|
||||||
friend AngleOf<T> operator*(const AngleOf<T> &angle, float factor) {
|
friend AngleOf<T> operator*(const AngleOf<T>& angle, float factor) {
|
||||||
return AngleOf::Degrees((float)angle.InDegrees() * factor);
|
return AngleOf::Degrees((float)angle.InDegrees() * factor);
|
||||||
}
|
}
|
||||||
/// @brief Multiplies the angle
|
/// @brief Multiplies the angle
|
||||||
/// @param factor The factor by which the angle is multiplies
|
/// @param factor The factor by which the angle is multiplies
|
||||||
/// @param angle The angle to multiply
|
/// @param angle The angle to multiply
|
||||||
/// @return The multiplied angle
|
/// @return The multiplied angle
|
||||||
friend AngleOf<T> operator*(float factor, const AngleOf<T> &angle) {
|
friend AngleOf<T> operator*(float factor, const AngleOf<T>& angle) {
|
||||||
return AngleOf::Degrees((float)factor * angle.InDegrees());
|
return AngleOf::Degrees((float)factor * angle.InDegrees());
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -150,7 +150,8 @@ public:
|
|||||||
/// @param toAngle The angle to rotate towards
|
/// @param toAngle The angle to rotate towards
|
||||||
/// @param maxAngle The maximum angle to rotate
|
/// @param maxAngle The maximum angle to rotate
|
||||||
/// @return The rotated angle
|
/// @return The rotated angle
|
||||||
static AngleOf<T> MoveTowards(AngleOf<T> fromAngle, AngleOf<T> toAngle,
|
static AngleOf<T> MoveTowards(AngleOf<T> fromAngle,
|
||||||
|
AngleOf<T> toAngle,
|
||||||
float maxAngle);
|
float maxAngle);
|
||||||
|
|
||||||
/// @brief Calculates the cosine of an angle
|
/// @brief Calculates the cosine of an angle
|
||||||
@ -205,7 +206,7 @@ public:
|
|||||||
/// @return The angle of the corner opposing side A
|
/// @return The angle of the corner opposing side A
|
||||||
static AngleOf<T> SineRuleAngle(float a, AngleOf<T> beta, float c);
|
static AngleOf<T> SineRuleAngle(float a, AngleOf<T> beta, float c);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
T value;
|
T value;
|
||||||
|
|
||||||
AngleOf<T>(T rawValue);
|
AngleOf<T>(T rawValue);
|
||||||
@ -215,8 +216,12 @@ using AngleSingle = AngleOf<float>;
|
|||||||
using Angle16 = AngleOf<signed short>;
|
using Angle16 = AngleOf<signed short>;
|
||||||
using Angle8 = AngleOf<signed char>;
|
using Angle8 = AngleOf<signed char>;
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
#if defined(ARDUINO)
|
||||||
} // namespace Passer
|
using Angle = Angle16;
|
||||||
using namespace Passer::LinearAlgebra;
|
#else
|
||||||
|
using Angle = AngleSingle;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
} // namespace LinearAlgebra
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -9,7 +9,8 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
template <typename T> DirectionOf<T>::DirectionOf() {
|
template <typename T>
|
||||||
|
DirectionOf<T>::DirectionOf() {
|
||||||
this->horizontal = AngleOf<T>();
|
this->horizontal = AngleOf<T>();
|
||||||
this->vertical = AngleOf<T>();
|
this->vertical = AngleOf<T>();
|
||||||
}
|
}
|
||||||
@ -41,7 +42,7 @@ const DirectionOf<T> DirectionOf<T>::right =
|
|||||||
DirectionOf<T>(AngleOf<T>::Degrees(90), AngleOf<T>());
|
DirectionOf<T>(AngleOf<T>::Degrees(90), AngleOf<T>());
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
Vector3 Passer::LinearAlgebra::DirectionOf<T>::ToVector3() const {
|
Vector3 DirectionOf<T>::ToVector3() const {
|
||||||
Quaternion q = Quaternion::Euler(-this->vertical.InDegrees(),
|
Quaternion q = Quaternion::Euler(-this->vertical.InDegrees(),
|
||||||
this->horizontal.InDegrees(), 0);
|
this->horizontal.InDegrees(), 0);
|
||||||
Vector3 v = q * Vector3::forward;
|
Vector3 v = q * Vector3::forward;
|
||||||
@ -49,49 +50,47 @@ Vector3 Passer::LinearAlgebra::DirectionOf<T>::ToVector3() const {
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
DirectionOf<T>
|
DirectionOf<T> DirectionOf<T>::FromVector3(Vector3 vector) {
|
||||||
Passer::LinearAlgebra::DirectionOf<T>::FromVector3(Vector3 vector) {
|
|
||||||
DirectionOf<T> d;
|
DirectionOf<T> d;
|
||||||
d.horizontal = AngleOf<T>::Atan2(
|
d.horizontal = AngleOf<T>::Atan2(
|
||||||
vector.Right(),
|
vector.Right(),
|
||||||
vector.Forward()); // AngleOf<T>::Radians(atan2f(v.Right(), v.Forward()));
|
vector
|
||||||
|
.Forward()); // AngleOf<T>::Radians(atan2f(v.Right(), v.Forward()));
|
||||||
d.vertical =
|
d.vertical =
|
||||||
AngleOf<T>::Degrees(-90) -
|
AngleOf<T>::Degrees(-90) -
|
||||||
AngleOf<T>::Acos(
|
AngleOf<T>::Acos(
|
||||||
vector.Up()); // AngleOf<T>::Radians(-(0.5f * pi) - acosf(v.Up()));
|
vector.Up()); // AngleOf<T>::Radians(-(0.5f * pi) - acosf(v.Up()));
|
||||||
d.Normalize();
|
d.Normalize();
|
||||||
return d;
|
return d;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
DirectionOf<T> Passer::LinearAlgebra::DirectionOf<T>::Degrees(float horizontal,
|
DirectionOf<T> DirectionOf<T>::Degrees(float horizontal, float vertical) {
|
||||||
float vertical) {
|
|
||||||
return DirectionOf<T>(AngleOf<T>::Degrees(horizontal),
|
return DirectionOf<T>(AngleOf<T>::Degrees(horizontal),
|
||||||
AngleOf<T>::Degrees(vertical));
|
AngleOf<T>::Degrees(vertical));
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
DirectionOf<T> Passer::LinearAlgebra::DirectionOf<T>::Radians(float horizontal,
|
DirectionOf<T> DirectionOf<T>::Radians(float horizontal, float vertical) {
|
||||||
float vertical) {
|
|
||||||
return DirectionOf<T>(AngleOf<T>::Radians(horizontal),
|
return DirectionOf<T>(AngleOf<T>::Radians(horizontal),
|
||||||
AngleOf<T>::Radians(vertical));
|
AngleOf<T>::Radians(vertical));
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
bool Passer::LinearAlgebra::DirectionOf<T>::operator==(
|
bool DirectionOf<T>::operator==(const DirectionOf<T> direction) const {
|
||||||
const DirectionOf<T> direction) const {
|
|
||||||
return (this->horizontal == direction.horizontal) &&
|
return (this->horizontal == direction.horizontal) &&
|
||||||
(this->vertical == direction.vertical);
|
(this->vertical == direction.vertical);
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
DirectionOf<T> Passer::LinearAlgebra::DirectionOf<T>::operator-() const {
|
DirectionOf<T> DirectionOf<T>::operator-() const {
|
||||||
DirectionOf<T> r = DirectionOf<T>(this->horizontal + AngleOf<T>::Degrees(180),
|
DirectionOf<T> r = DirectionOf<T>(this->horizontal + AngleOf<T>::Degrees(180),
|
||||||
-this->vertical);
|
-this->vertical);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> void DirectionOf<T>::Normalize() {
|
template <typename T>
|
||||||
|
void DirectionOf<T>::Normalize() {
|
||||||
if (this->vertical > AngleOf<T>::Degrees(90) ||
|
if (this->vertical > AngleOf<T>::Degrees(90) ||
|
||||||
this->vertical < AngleOf<T>::Degrees(-90)) {
|
this->vertical < AngleOf<T>::Degrees(-90)) {
|
||||||
this->horizontal += AngleOf<T>::Degrees(180);
|
this->horizontal += AngleOf<T>::Degrees(180);
|
||||||
@ -99,5 +98,5 @@ template <typename T> void DirectionOf<T>::Normalize() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
template class Passer::LinearAlgebra::DirectionOf<float>;
|
template class DirectionOf<float>;
|
||||||
template class Passer::LinearAlgebra::DirectionOf<signed short>;
|
template class DirectionOf<signed short>;
|
||||||
|
@ -7,7 +7,6 @@
|
|||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
struct Vector3;
|
struct Vector3;
|
||||||
@ -22,8 +21,9 @@ struct Vector3;
|
|||||||
/// rotation has been applied.
|
/// rotation has been applied.
|
||||||
/// The angles are automatically normalized to stay within the abovenmentioned
|
/// The angles are automatically normalized to stay within the abovenmentioned
|
||||||
/// ranges.
|
/// ranges.
|
||||||
template <typename T> class DirectionOf {
|
template <typename T>
|
||||||
public:
|
class DirectionOf {
|
||||||
|
public:
|
||||||
/// @brief horizontal angle, range= (-180..180]
|
/// @brief horizontal angle, range= (-180..180]
|
||||||
AngleOf<T> horizontal;
|
AngleOf<T> horizontal;
|
||||||
/// @brief vertical angle, range in degrees = (-90..90]
|
/// @brief vertical angle, range in degrees = (-90..90]
|
||||||
@ -83,7 +83,7 @@ public:
|
|||||||
/// @return The reversed direction.
|
/// @return The reversed direction.
|
||||||
DirectionOf<T> operator-() const;
|
DirectionOf<T> operator-() const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief Normalize this vector to the specified ranges
|
/// @brief Normalize this vector to the specified ranges
|
||||||
void Normalize();
|
void Normalize();
|
||||||
};
|
};
|
||||||
@ -97,8 +97,8 @@ using Direction = Direction16;
|
|||||||
using Direction = DirectionSingle;
|
using Direction = DirectionSingle;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
|
||||||
using namespace Passer::LinearAlgebra;
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -5,19 +5,18 @@
|
|||||||
#ifndef FLOAT_H
|
#ifndef FLOAT_H
|
||||||
#define FLOAT_H
|
#define FLOAT_H
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
class Float {
|
class Float {
|
||||||
public:
|
public:
|
||||||
static const float epsilon;
|
static const float epsilon;
|
||||||
static const float sqrEpsilon;
|
static const float sqrEpsilon;
|
||||||
|
|
||||||
static float Clamp(float f, float min, float max);
|
static float Clamp(float f, float min, float max);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
|
||||||
using namespace Passer::LinearAlgebra;
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -3,18 +3,18 @@
|
|||||||
|
|
||||||
#include "Vector3.h"
|
#include "Vector3.h"
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
/// @brief Single precision float matrix
|
/// @brief Single precision float matrix
|
||||||
template <typename T> class MatrixOf {
|
template <typename T>
|
||||||
public:
|
class MatrixOf {
|
||||||
|
public:
|
||||||
MatrixOf(unsigned int rows, unsigned int cols);
|
MatrixOf(unsigned int rows, unsigned int cols);
|
||||||
MatrixOf(unsigned int rows, unsigned int cols, const T *source)
|
MatrixOf(unsigned int rows, unsigned int cols, const T* source)
|
||||||
: MatrixOf(rows, cols) {
|
: MatrixOf(rows, cols) {
|
||||||
Set(source);
|
Set(source);
|
||||||
}
|
}
|
||||||
MatrixOf(Vector3 v); // creates a 3,1 matrix
|
MatrixOf(Vector3 v); // creates a 3,1 matrix
|
||||||
|
|
||||||
~MatrixOf() {
|
~MatrixOf() {
|
||||||
if (this->data == nullptr)
|
if (this->data == nullptr)
|
||||||
@ -25,7 +25,7 @@ public:
|
|||||||
|
|
||||||
/// @brief Transpose with result in matrix m
|
/// @brief Transpose with result in matrix m
|
||||||
/// @param r The matrix in which the transposed matrix is stored
|
/// @param r The matrix in which the transposed matrix is stored
|
||||||
void Transpose(MatrixOf<T> *r) const {
|
void Transpose(MatrixOf<T>* r) const {
|
||||||
// Check dimensions first
|
// Check dimensions first
|
||||||
// We dont care about the rows and cols (we overwrite them)
|
// We dont care about the rows and cols (we overwrite them)
|
||||||
// but the data size should be equal to avoid problems
|
// but the data size should be equal to avoid problems
|
||||||
@ -54,13 +54,14 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void Multiply(const MatrixOf<T> *m1, const MatrixOf<T> *m2,
|
static void Multiply(const MatrixOf<T>* m1,
|
||||||
MatrixOf<T> *r);
|
const MatrixOf<T>* m2,
|
||||||
void Multiply(const MatrixOf<T> *m, MatrixOf<T> *r) const {
|
MatrixOf<T>* r);
|
||||||
|
void Multiply(const MatrixOf<T>* m, MatrixOf<T>* r) const {
|
||||||
Multiply(this, m, r);
|
Multiply(this, m, r);
|
||||||
}
|
}
|
||||||
|
|
||||||
static Vector3 Multiply(const MatrixOf<T> *m, Vector3 v);
|
static Vector3 Multiply(const MatrixOf<T>* m, Vector3 v);
|
||||||
Vector3 operator*(const Vector3 v) const;
|
Vector3 operator*(const Vector3 v) const;
|
||||||
|
|
||||||
T Get(unsigned int rowIx, unsigned int colIx) const {
|
T Get(unsigned int rowIx, unsigned int colIx) const {
|
||||||
@ -74,28 +75,28 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// This function does not check on source size!
|
// This function does not check on source size!
|
||||||
void Set(const T *source) {
|
void Set(const T* source) {
|
||||||
unsigned int matrixSize = this->cols * this->rows;
|
unsigned int matrixSize = this->cols * this->rows;
|
||||||
for (unsigned int dataIx = 0; dataIx < matrixSize; dataIx++)
|
for (unsigned int dataIx = 0; dataIx < matrixSize; dataIx++)
|
||||||
this->data[dataIx] = source[dataIx];
|
this->data[dataIx] = source[dataIx];
|
||||||
}
|
}
|
||||||
|
|
||||||
// This function does not check on source size!
|
// This function does not check on source size!
|
||||||
void SetRow(unsigned int rowIx, const T *source) {
|
void SetRow(unsigned int rowIx, const T* source) {
|
||||||
unsigned int dataIx = rowIx * this->cols;
|
unsigned int dataIx = rowIx * this->cols;
|
||||||
for (unsigned int sourceIx = 0; sourceIx < this->cols; dataIx++, sourceIx++)
|
for (unsigned int sourceIx = 0; sourceIx < this->cols; dataIx++, sourceIx++)
|
||||||
this->data[dataIx] = source[sourceIx];
|
this->data[dataIx] = source[sourceIx];
|
||||||
}
|
}
|
||||||
|
|
||||||
// This function does not check on source size!
|
// This function does not check on source size!
|
||||||
void SetCol(unsigned int colIx, const T *source) {
|
void SetCol(unsigned int colIx, const T* source) {
|
||||||
unsigned int dataIx = colIx;
|
unsigned int dataIx = colIx;
|
||||||
for (unsigned int sourceIx = 0; sourceIx < this->cols;
|
for (unsigned int sourceIx = 0; sourceIx < this->cols;
|
||||||
dataIx += this->cols, sourceIx++)
|
dataIx += this->cols, sourceIx++)
|
||||||
this->data[dataIx] = source[sourceIx];
|
this->data[dataIx] = source[sourceIx];
|
||||||
}
|
}
|
||||||
|
|
||||||
void CopyFrom(const MatrixOf<T> *m) {
|
void CopyFrom(const MatrixOf<T>* m) {
|
||||||
unsigned int thisMatrixSize = this->cols * this->rows;
|
unsigned int thisMatrixSize = this->cols * this->rows;
|
||||||
unsigned int mMatrixSize = m->cols * m->rows;
|
unsigned int mMatrixSize = m->cols * m->rows;
|
||||||
if (mMatrixSize != thisMatrixSize)
|
if (mMatrixSize != thisMatrixSize)
|
||||||
@ -108,14 +109,13 @@ public:
|
|||||||
unsigned int RowCount() const { return rows; }
|
unsigned int RowCount() const { return rows; }
|
||||||
unsigned int ColCount() const { return cols; }
|
unsigned int ColCount() const { return cols; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
unsigned int rows;
|
unsigned int rows;
|
||||||
unsigned int cols;
|
unsigned int cols;
|
||||||
T *data;
|
T* data;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -3,11 +3,13 @@
|
|||||||
#include "Polar.h"
|
#include "Polar.h"
|
||||||
#include "Vector2.h"
|
#include "Vector2.h"
|
||||||
|
|
||||||
template <typename T> PolarOf<T>::PolarOf() {
|
template <typename T>
|
||||||
|
PolarOf<T>::PolarOf() {
|
||||||
this->distance = 0.0f;
|
this->distance = 0.0f;
|
||||||
this->angle = AngleOf<T>();
|
this->angle = AngleOf<T>();
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T>::PolarOf(float distance, AngleOf<T> angle) {
|
template <typename T>
|
||||||
|
PolarOf<T>::PolarOf(float distance, AngleOf<T> angle) {
|
||||||
// distance should always be 0 or greater
|
// distance should always be 0 or greater
|
||||||
if (distance < 0.0f) {
|
if (distance < 0.0f) {
|
||||||
this->distance = -distance;
|
this->distance = -distance;
|
||||||
@ -34,16 +36,18 @@ PolarOf<T> PolarOf<T>::Radians(float distance, float radians) {
|
|||||||
return PolarOf<T>(distance, AngleOf<T>::Radians(radians));
|
return PolarOf<T>(distance, AngleOf<T>::Radians(radians));
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::FromVector2(Vector2 v) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::FromVector2(Vector2 v) {
|
||||||
float distance = v.magnitude();
|
float distance = v.magnitude();
|
||||||
AngleOf<T> angle =
|
AngleOf<T> angle =
|
||||||
AngleOf<T>::Degrees(Vector2::SignedAngle(Vector2::forward, v));
|
AngleOf<T>::Degrees(Vector2::SignedAngle(Vector2::forward, v));
|
||||||
PolarOf<T> p = PolarOf(distance, angle);
|
PolarOf<T> p = PolarOf(distance, angle);
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::FromSpherical(SphericalOf<T> v) {
|
template <typename T>
|
||||||
float distance = v.distance * cosf(v.direction.vertical.InDegrees() *
|
PolarOf<T> PolarOf<T>::FromSpherical(SphericalOf<T> v) {
|
||||||
Passer::LinearAlgebra::Deg2Rad);
|
float distance =
|
||||||
|
v.distance * cosf(v.direction.vertical.InDegrees() * Deg2Rad);
|
||||||
AngleOf<T> angle = v.direction.horizontal;
|
AngleOf<T> angle = v.direction.horizontal;
|
||||||
PolarOf<T> p = PolarOf(distance, angle);
|
PolarOf<T> p = PolarOf(distance, angle);
|
||||||
return p;
|
return p;
|
||||||
@ -60,31 +64,37 @@ const PolarOf<T> PolarOf<T>::right = PolarOf(1.0, AngleOf<T>::Degrees(90));
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
const PolarOf<T> PolarOf<T>::left = PolarOf(1.0, AngleOf<T>::Degrees(-90));
|
const PolarOf<T> PolarOf<T>::left = PolarOf(1.0, AngleOf<T>::Degrees(-90));
|
||||||
|
|
||||||
template <typename T> bool PolarOf<T>::operator==(const PolarOf &v) const {
|
template <typename T>
|
||||||
|
bool PolarOf<T>::operator==(const PolarOf& v) const {
|
||||||
return (this->distance == v.distance &&
|
return (this->distance == v.distance &&
|
||||||
this->angle.InDegrees() == v.angle.InDegrees());
|
this->angle.InDegrees() == v.angle.InDegrees());
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::Normalize(const PolarOf &v) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::Normalize(const PolarOf& v) {
|
||||||
PolarOf<T> r = PolarOf(1, v.angle);
|
PolarOf<T> r = PolarOf(1, v.angle);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::normalized() const {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::normalized() const {
|
||||||
PolarOf<T> r = PolarOf(1, this->angle);
|
PolarOf<T> r = PolarOf(1, this->angle);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator-() const {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator-() const {
|
||||||
PolarOf<T> v =
|
PolarOf<T> v =
|
||||||
PolarOf(this->distance, this->angle + AngleOf<T>::Degrees(180));
|
PolarOf(this->distance, this->angle + AngleOf<T>::Degrees(180));
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator-(const PolarOf &v) const {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator-(const PolarOf& v) const {
|
||||||
PolarOf<T> r = -v;
|
PolarOf<T> r = -v;
|
||||||
return *this + r;
|
return *this + r;
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator-=(const PolarOf &v) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator-=(const PolarOf& v) {
|
||||||
*this = *this - v;
|
*this = *this - v;
|
||||||
return *this;
|
return *this;
|
||||||
// angle = AngleOf<T>::Normalize(newAngle);
|
// angle = AngleOf<T>::Normalize(newAngle);
|
||||||
@ -105,7 +115,8 @@ template <typename T> PolarOf<T> PolarOf<T>::operator-=(const PolarOf &v) {
|
|||||||
// return d;
|
// return d;
|
||||||
// }
|
// }
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator+(const PolarOf &v) const {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator+(const PolarOf& v) const {
|
||||||
if (v.distance == 0)
|
if (v.distance == 0)
|
||||||
return PolarOf(this->distance, this->angle);
|
return PolarOf(this->distance, this->angle);
|
||||||
if (this->distance == 0.0f)
|
if (this->distance == 0.0f)
|
||||||
@ -133,33 +144,36 @@ template <typename T> PolarOf<T> PolarOf<T>::operator+(const PolarOf &v) const {
|
|||||||
PolarOf vector = PolarOf(newDistance, newAngleA);
|
PolarOf vector = PolarOf(newDistance, newAngleA);
|
||||||
return vector;
|
return vector;
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator+=(const PolarOf &v) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator+=(const PolarOf& v) {
|
||||||
*this = *this + v;
|
*this = *this + v;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator*=(float f) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator*=(float f) {
|
||||||
this->distance *= f;
|
this->distance *= f;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
template <typename T> PolarOf<T> PolarOf<T>::operator/=(float f) {
|
template <typename T>
|
||||||
|
PolarOf<T> PolarOf<T>::operator/=(float f) {
|
||||||
this->distance /= f;
|
this->distance /= f;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
float PolarOf<T>::Distance(const PolarOf &v1, const PolarOf &v2) {
|
float PolarOf<T>::Distance(const PolarOf& v1, const PolarOf& v2) {
|
||||||
float d =
|
float d =
|
||||||
AngleOf<T>::CosineRuleSide(v1.distance, v2.distance, v2.angle - v1.angle);
|
AngleOf<T>::CosineRuleSide(v1.distance, v2.distance, v2.angle - v1.angle);
|
||||||
return d;
|
return d;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
PolarOf<T> PolarOf<T>::Rotate(const PolarOf &v, AngleOf<T> angle) {
|
PolarOf<T> PolarOf<T>::Rotate(const PolarOf& v, AngleOf<T> angle) {
|
||||||
AngleOf<T> a = AngleOf<T>::Normalize(v.angle + angle);
|
AngleOf<T> a = AngleOf<T>::Normalize(v.angle + angle);
|
||||||
PolarOf<T> r = PolarOf(v.distance, a);
|
PolarOf<T> r = PolarOf(v.distance, a);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template class Passer::LinearAlgebra::PolarOf<float>;
|
template class PolarOf<float>;
|
||||||
template class Passer::LinearAlgebra::PolarOf<signed short>;
|
template class PolarOf<signed short>;
|
@ -7,16 +7,17 @@
|
|||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
struct Vector2;
|
struct Vector2;
|
||||||
template <typename T> class SphericalOf;
|
template <typename T>
|
||||||
|
class SphericalOf;
|
||||||
|
|
||||||
/// @brief A polar vector using an angle in various representations
|
/// @brief A polar vector using an angle in various representations
|
||||||
/// @tparam T The implementation type used for the representation of the angle
|
/// @tparam T The implementation type used for the representation of the angle
|
||||||
template <typename T> class PolarOf {
|
template <typename T>
|
||||||
public:
|
class PolarOf {
|
||||||
|
public:
|
||||||
/// @brief The distance in meters
|
/// @brief The distance in meters
|
||||||
/// @remark The distance shall never be negative
|
/// @remark The distance shall never be negative
|
||||||
float distance;
|
float distance;
|
||||||
@ -76,12 +77,12 @@ public:
|
|||||||
/// @return true: if it is identical to the given vector
|
/// @return true: if it is identical to the given vector
|
||||||
/// @note This uses float comparison to check equality which may have
|
/// @note This uses float comparison to check equality which may have
|
||||||
/// strange effects. Equality on floats should be avoided.
|
/// strange effects. Equality on floats should be avoided.
|
||||||
bool operator==(const PolarOf &v) const;
|
bool operator==(const PolarOf& v) const;
|
||||||
|
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @param v The vector for which you need the length
|
/// @param v The vector for which you need the length
|
||||||
/// @return The vector length;
|
/// @return The vector length;
|
||||||
inline static float Magnitude(const PolarOf &v) { return v.distance; }
|
inline static float Magnitude(const PolarOf& v) { return v.distance; }
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @return The vector length
|
/// @return The vector length
|
||||||
inline float magnitude() const { return this->distance; }
|
inline float magnitude() const { return this->distance; }
|
||||||
@ -89,7 +90,7 @@ public:
|
|||||||
/// @brief Convert the vector to a length of 1
|
/// @brief Convert the vector to a length of 1
|
||||||
/// @param v The vector to convert
|
/// @param v The vector to convert
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
static PolarOf Normalize(const PolarOf &v);
|
static PolarOf Normalize(const PolarOf& v);
|
||||||
/// @brief Convert the vector to a length of a
|
/// @brief Convert the vector to a length of a
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
PolarOf normalized() const;
|
PolarOf normalized() const;
|
||||||
@ -102,23 +103,23 @@ public:
|
|||||||
/// @brief Subtract a polar vector from this vector
|
/// @brief Subtract a polar vector from this vector
|
||||||
/// @param v The vector to subtract
|
/// @param v The vector to subtract
|
||||||
/// @return The result of the subtraction
|
/// @return The result of the subtraction
|
||||||
PolarOf operator-(const PolarOf &v) const;
|
PolarOf operator-(const PolarOf& v) const;
|
||||||
PolarOf operator-=(const PolarOf &v);
|
PolarOf operator-=(const PolarOf& v);
|
||||||
/// @brief Add a polar vector to this vector
|
/// @brief Add a polar vector to this vector
|
||||||
/// @param v The vector to add
|
/// @param v The vector to add
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
PolarOf operator+(const PolarOf &v) const;
|
PolarOf operator+(const PolarOf& v) const;
|
||||||
PolarOf operator+=(const PolarOf &v);
|
PolarOf operator+=(const PolarOf& v);
|
||||||
|
|
||||||
/// @brief Scale the vector uniformly up
|
/// @brief Scale the vector uniformly up
|
||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark This operation will scale the distance of the vector. The angle
|
/// @remark This operation will scale the distance of the vector. The angle
|
||||||
/// will be unaffected.
|
/// will be unaffected.
|
||||||
friend PolarOf operator*(const PolarOf &v, float f) {
|
friend PolarOf operator*(const PolarOf& v, float f) {
|
||||||
return PolarOf(v.distance * f, v.angle);
|
return PolarOf(v.distance * f, v.angle);
|
||||||
}
|
}
|
||||||
friend PolarOf operator*(float f, const PolarOf &v) {
|
friend PolarOf operator*(float f, const PolarOf& v) {
|
||||||
return PolarOf(f * v.distance, v.angle);
|
return PolarOf(f * v.distance, v.angle);
|
||||||
}
|
}
|
||||||
PolarOf operator*=(float f);
|
PolarOf operator*=(float f);
|
||||||
@ -127,10 +128,10 @@ public:
|
|||||||
/// @return The scaled factor
|
/// @return The scaled factor
|
||||||
/// @remark This operation will scale the distance of the vector. The angle
|
/// @remark This operation will scale the distance of the vector. The angle
|
||||||
/// will be unaffected.
|
/// will be unaffected.
|
||||||
friend PolarOf operator/(const PolarOf &v, float f) {
|
friend PolarOf operator/(const PolarOf& v, float f) {
|
||||||
return PolarOf(v.distance / f, v.angle);
|
return PolarOf(v.distance / f, v.angle);
|
||||||
}
|
}
|
||||||
friend PolarOf operator/(float f, const PolarOf &v) {
|
friend PolarOf operator/(float f, const PolarOf& v) {
|
||||||
return PolarOf(f / v.distance, v.angle);
|
return PolarOf(f / v.distance, v.angle);
|
||||||
}
|
}
|
||||||
PolarOf operator/=(float f);
|
PolarOf operator/=(float f);
|
||||||
@ -139,22 +140,21 @@ public:
|
|||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The distance between the two vectors
|
/// @return The distance between the two vectors
|
||||||
static float Distance(const PolarOf &v1, const PolarOf &v2);
|
static float Distance(const PolarOf& v1, const PolarOf& v2);
|
||||||
|
|
||||||
/// @brief Rotate a vector
|
/// @brief Rotate a vector
|
||||||
/// @param v The vector to rotate
|
/// @param v The vector to rotate
|
||||||
/// @param a The angle in degreesto rotate
|
/// @param a The angle in degreesto rotate
|
||||||
/// @return The rotated vector
|
/// @return The rotated vector
|
||||||
static PolarOf Rotate(const PolarOf &v, AngleOf<T> a);
|
static PolarOf Rotate(const PolarOf& v, AngleOf<T> a);
|
||||||
};
|
};
|
||||||
|
|
||||||
using PolarSingle = PolarOf<float>;
|
using PolarSingle = PolarOf<float>;
|
||||||
using Polar16 = PolarOf<signed short>;
|
using Polar16 = PolarOf<signed short>;
|
||||||
// using Polar = PolarSingle;
|
// using Polar = PolarSingle;
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
#include "Vector2.h"
|
#include "Vector2.h"
|
||||||
|
@ -32,14 +32,13 @@ typedef struct Quat {
|
|||||||
} Quat;
|
} Quat;
|
||||||
}
|
}
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// A quaternion
|
/// A quaternion
|
||||||
/// </summary>
|
/// </summary>
|
||||||
struct Quaternion : Quat {
|
struct Quaternion : Quat {
|
||||||
public:
|
public:
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Create a new identity quaternion
|
/// Create a new identity quaternion
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -80,7 +79,7 @@ public:
|
|||||||
/// <returns>A unit quaternion</returns>
|
/// <returns>A unit quaternion</returns>
|
||||||
/// This will preserve the orientation,
|
/// This will preserve the orientation,
|
||||||
/// but ensures that it is a unit quaternion.
|
/// but ensures that it is a unit quaternion.
|
||||||
static Quaternion Normalize(const Quaternion &q);
|
static Quaternion Normalize(const Quaternion& q);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Convert to euler angles
|
/// Convert to euler angles
|
||||||
@ -88,14 +87,14 @@ public:
|
|||||||
/// <param name="q">The quaternion to convert</param>
|
/// <param name="q">The quaternion to convert</param>
|
||||||
/// <returns>A vector containing euler angles</returns>
|
/// <returns>A vector containing euler angles</returns>
|
||||||
/// The euler angles performed in the order: Z, X, Y
|
/// The euler angles performed in the order: Z, X, Y
|
||||||
static Vector3 ToAngles(const Quaternion &q);
|
static Vector3 ToAngles(const Quaternion& q);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Rotate a vector using this quaterion
|
/// Rotate a vector using this quaterion
|
||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="vector">The vector to rotate</param>
|
/// <param name="vector">The vector to rotate</param>
|
||||||
/// <returns>The rotated vector</returns>
|
/// <returns>The rotated vector</returns>
|
||||||
Vector3 operator*(const Vector3 &vector) const;
|
Vector3 operator*(const Vector3& vector) const;
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Multiply this quaternion with another quaternion
|
/// Multiply this quaternion with another quaternion
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -103,7 +102,7 @@ public:
|
|||||||
/// <returns>The resulting rotation</returns>
|
/// <returns>The resulting rotation</returns>
|
||||||
/// The result will be this quaternion rotated according to
|
/// The result will be this quaternion rotated according to
|
||||||
/// the give rotation.
|
/// the give rotation.
|
||||||
Quaternion operator*(const Quaternion &rotation) const;
|
Quaternion operator*(const Quaternion& rotation) const;
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Check the equality of two quaternions
|
/// Check the equality of two quaternions
|
||||||
@ -114,7 +113,7 @@ public:
|
|||||||
/// themselves. Two quaternions with the same rotational effect may have
|
/// themselves. Two quaternions with the same rotational effect may have
|
||||||
/// different components. Use Quaternion::Angle to check if the rotations are
|
/// different components. Use Quaternion::Angle to check if the rotations are
|
||||||
/// the same.
|
/// the same.
|
||||||
bool operator==(const Quaternion &quaternion) const;
|
bool operator==(const Quaternion& quaternion) const;
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// The inverse of quaterion
|
/// The inverse of quaterion
|
||||||
@ -129,8 +128,8 @@ public:
|
|||||||
/// <param name="forward">The look direction</param>
|
/// <param name="forward">The look direction</param>
|
||||||
/// <param name="upwards">The up direction</param>
|
/// <param name="upwards">The up direction</param>
|
||||||
/// <returns>The look rotation</returns>
|
/// <returns>The look rotation</returns>
|
||||||
static Quaternion LookRotation(const Vector3 &forward,
|
static Quaternion LookRotation(const Vector3& forward,
|
||||||
const Vector3 &upwards);
|
const Vector3& upwards);
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Creates a quaternion with the given forward direction with up =
|
/// Creates a quaternion with the given forward direction with up =
|
||||||
/// Vector3::up
|
/// Vector3::up
|
||||||
@ -140,7 +139,7 @@ public:
|
|||||||
/// For the rotation, Vector::up is used for the up direction.
|
/// For the rotation, Vector::up is used for the up direction.
|
||||||
/// Note: if the forward direction == Vector3::up, the result is
|
/// Note: if the forward direction == Vector3::up, the result is
|
||||||
/// Quaternion::identity
|
/// Quaternion::identity
|
||||||
static Quaternion LookRotation(const Vector3 &forward);
|
static Quaternion LookRotation(const Vector3& forward);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Calculat the rotation from on vector to another
|
/// Calculat the rotation from on vector to another
|
||||||
@ -157,7 +156,8 @@ public:
|
|||||||
/// <param name="to">The destination rotation</param>
|
/// <param name="to">The destination rotation</param>
|
||||||
/// <param name="maxDegreesDelta">The maximum amount of degrees to
|
/// <param name="maxDegreesDelta">The maximum amount of degrees to
|
||||||
/// rotate</param> <returns>The possibly limited rotation</returns>
|
/// rotate</param> <returns>The possibly limited rotation</returns>
|
||||||
static Quaternion RotateTowards(const Quaternion &from, const Quaternion &to,
|
static Quaternion RotateTowards(const Quaternion& from,
|
||||||
|
const Quaternion& to,
|
||||||
float maxDegreesDelta);
|
float maxDegreesDelta);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -166,13 +166,13 @@ public:
|
|||||||
/// <param name="angle">The angle</param>
|
/// <param name="angle">The angle</param>
|
||||||
/// <param name="axis">The axis</param>
|
/// <param name="axis">The axis</param>
|
||||||
/// <returns>The resulting quaternion</returns>
|
/// <returns>The resulting quaternion</returns>
|
||||||
static Quaternion AngleAxis(float angle, const Vector3 &axis);
|
static Quaternion AngleAxis(float angle, const Vector3& axis);
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Convert this quaternion to angle/axis representation
|
/// Convert this quaternion to angle/axis representation
|
||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="angle">A pointer to the angle for the result</param>
|
/// <param name="angle">A pointer to the angle for the result</param>
|
||||||
/// <param name="axis">A pointer to the axis for the result</param>
|
/// <param name="axis">A pointer to the axis for the result</param>
|
||||||
void ToAngleAxis(float *angle, Vector3 *axis);
|
void ToAngleAxis(float* angle, Vector3* axis);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Get the angle between two orientations
|
/// Get the angle between two orientations
|
||||||
@ -190,8 +190,9 @@ public:
|
|||||||
/// <param name="factor">The factor between 0 and 1.</param>
|
/// <param name="factor">The factor between 0 and 1.</param>
|
||||||
/// <returns>The resulting rotation</returns>
|
/// <returns>The resulting rotation</returns>
|
||||||
/// A factor 0 returns rotation1, factor1 returns rotation2.
|
/// A factor 0 returns rotation1, factor1 returns rotation2.
|
||||||
static Quaternion Slerp(const Quaternion &rotation1,
|
static Quaternion Slerp(const Quaternion& rotation1,
|
||||||
const Quaternion &rotation2, float factor);
|
const Quaternion& rotation2,
|
||||||
|
float factor);
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Unclamped sherical lerp between two rotations
|
/// Unclamped sherical lerp between two rotations
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -201,8 +202,9 @@ public:
|
|||||||
/// <returns>The resulting rotation</returns>
|
/// <returns>The resulting rotation</returns>
|
||||||
/// A factor 0 returns rotation1, factor1 returns rotation2.
|
/// A factor 0 returns rotation1, factor1 returns rotation2.
|
||||||
/// Values outside the 0..1 range will result in extrapolated rotations
|
/// Values outside the 0..1 range will result in extrapolated rotations
|
||||||
static Quaternion SlerpUnclamped(const Quaternion &rotation1,
|
static Quaternion SlerpUnclamped(const Quaternion& rotation1,
|
||||||
const Quaternion &rotation2, float factor);
|
const Quaternion& rotation2,
|
||||||
|
float factor);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Create a rotation from euler angles
|
/// Create a rotation from euler angles
|
||||||
@ -260,8 +262,10 @@ public:
|
|||||||
/// <param name="swing">A pointer to the quaternion for the swing
|
/// <param name="swing">A pointer to the quaternion for the swing
|
||||||
/// result</param> <param name="twist">A pointer to the quaternion for the
|
/// result</param> <param name="twist">A pointer to the quaternion for the
|
||||||
/// twist result</param>
|
/// twist result</param>
|
||||||
static void GetSwingTwist(Vector3 axis, Quaternion rotation,
|
static void GetSwingTwist(Vector3 axis,
|
||||||
Quaternion *swing, Quaternion *twist);
|
Quaternion rotation,
|
||||||
|
Quaternion* swing,
|
||||||
|
Quaternion* twist);
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Calculate the dot product of two quaternions
|
/// Calculate the dot product of two quaternions
|
||||||
@ -271,20 +275,19 @@ public:
|
|||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
static float Dot(Quaternion rotation1, Quaternion rotation2);
|
static float Dot(Quaternion rotation1, Quaternion rotation2);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float GetLength() const;
|
float GetLength() const;
|
||||||
float GetLengthSquared() const;
|
float GetLengthSquared() const;
|
||||||
static float GetLengthSquared(const Quaternion &q);
|
static float GetLengthSquared(const Quaternion& q);
|
||||||
|
|
||||||
void ToAxisAngleRad(const Quaternion &q, Vector3 *const axis, float *angle);
|
void ToAxisAngleRad(const Quaternion& q, Vector3* const axis, float* angle);
|
||||||
static Quaternion FromEulerRad(Vector3 euler);
|
static Quaternion FromEulerRad(Vector3 euler);
|
||||||
static Quaternion FromEulerRadXYZ(Vector3 euler);
|
static Quaternion FromEulerRadXYZ(Vector3 euler);
|
||||||
|
|
||||||
Vector3 xyz() const;
|
Vector3 xyz() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -5,13 +5,15 @@
|
|||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
template <typename T> SphericalOf<T>::SphericalOf() {
|
template <typename T>
|
||||||
|
SphericalOf<T>::SphericalOf() {
|
||||||
this->distance = 0.0f;
|
this->distance = 0.0f;
|
||||||
this->direction = DirectionOf<T>();
|
this->direction = DirectionOf<T>();
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T>::SphericalOf(float distance, AngleOf<T> horizontal,
|
SphericalOf<T>::SphericalOf(float distance,
|
||||||
|
AngleOf<T> horizontal,
|
||||||
AngleOf<T> vertical) {
|
AngleOf<T> vertical) {
|
||||||
if (distance < 0) {
|
if (distance < 0) {
|
||||||
this->distance = -distance;
|
this->distance = -distance;
|
||||||
@ -34,7 +36,8 @@ SphericalOf<T>::SphericalOf(float distance, DirectionOf<T> direction) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::Degrees(float distance, float horizontal,
|
SphericalOf<T> SphericalOf<T>::Degrees(float distance,
|
||||||
|
float horizontal,
|
||||||
float vertical) {
|
float vertical) {
|
||||||
AngleOf<T> horizontalAngle = AngleOf<T>::Degrees(horizontal);
|
AngleOf<T> horizontalAngle = AngleOf<T>::Degrees(horizontal);
|
||||||
AngleOf<T> verticalAngle = AngleOf<T>::Degrees(vertical);
|
AngleOf<T> verticalAngle = AngleOf<T>::Degrees(vertical);
|
||||||
@ -43,7 +46,8 @@ SphericalOf<T> SphericalOf<T>::Degrees(float distance, float horizontal,
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::Radians(float distance, float horizontal,
|
SphericalOf<T> SphericalOf<T>::Radians(float distance,
|
||||||
|
float horizontal,
|
||||||
float vertical) {
|
float vertical) {
|
||||||
return SphericalOf<T>(distance, AngleOf<T>::Radians(horizontal),
|
return SphericalOf<T>(distance, AngleOf<T>::Radians(horizontal),
|
||||||
AngleOf<T>::Radians(vertical));
|
AngleOf<T>::Radians(vertical));
|
||||||
@ -57,7 +61,8 @@ SphericalOf<T> SphericalOf<T>::FromPolar(PolarOf<T> polar) {
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> SphericalOf<T> SphericalOf<T>::FromVector3(Vector3 v) {
|
template <typename T>
|
||||||
|
SphericalOf<T> SphericalOf<T>::FromVector3(Vector3 v) {
|
||||||
float distance = v.magnitude();
|
float distance = v.magnitude();
|
||||||
if (distance == 0.0f) {
|
if (distance == 0.0f) {
|
||||||
return SphericalOf(distance, AngleOf<T>(), AngleOf<T>());
|
return SphericalOf(distance, AngleOf<T>(), AngleOf<T>());
|
||||||
@ -81,7 +86,8 @@ template <typename T> SphericalOf<T> SphericalOf<T>::FromVector3(Vector3 v) {
|
|||||||
* @tparam T The type of the distance and direction values.
|
* @tparam T The type of the distance and direction values.
|
||||||
* @return Vector3 The 3D vector representation of the spherical coordinates.
|
* @return Vector3 The 3D vector representation of the spherical coordinates.
|
||||||
*/
|
*/
|
||||||
template <typename T> Vector3 SphericalOf<T>::ToVector3() const {
|
template <typename T>
|
||||||
|
Vector3 SphericalOf<T>::ToVector3() const {
|
||||||
float verticalRad = (pi / 2) - this->direction.vertical.InRadians();
|
float verticalRad = (pi / 2) - this->direction.vertical.InRadians();
|
||||||
float horizontalRad = this->direction.horizontal.InRadians();
|
float horizontalRad = this->direction.horizontal.InRadians();
|
||||||
|
|
||||||
@ -126,7 +132,8 @@ SphericalOf<T> SphericalOf<T>::WithDistance(float distance) {
|
|||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> SphericalOf<T> SphericalOf<T>::operator-() const {
|
template <typename T>
|
||||||
|
SphericalOf<T> SphericalOf<T>::operator-() const {
|
||||||
SphericalOf<T> v = SphericalOf<T>(
|
SphericalOf<T> v = SphericalOf<T>(
|
||||||
this->distance, this->direction.horizontal + AngleOf<T>::Degrees(180),
|
this->distance, this->direction.horizontal + AngleOf<T>::Degrees(180),
|
||||||
this->direction.vertical + AngleOf<T>::Degrees(180));
|
this->direction.vertical + AngleOf<T>::Degrees(180));
|
||||||
@ -134,7 +141,7 @@ template <typename T> SphericalOf<T> SphericalOf<T>::operator-() const {
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::operator-(const SphericalOf<T> &s2) const {
|
SphericalOf<T> SphericalOf<T>::operator-(const SphericalOf<T>& s2) const {
|
||||||
// let's do it the easy way...
|
// let's do it the easy way...
|
||||||
Vector3 v1 = this->ToVector3();
|
Vector3 v1 = this->ToVector3();
|
||||||
Vector3 v2 = s2.ToVector3();
|
Vector3 v2 = s2.ToVector3();
|
||||||
@ -143,13 +150,13 @@ SphericalOf<T> SphericalOf<T>::operator-(const SphericalOf<T> &s2) const {
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::operator-=(const SphericalOf<T> &v) {
|
SphericalOf<T> SphericalOf<T>::operator-=(const SphericalOf<T>& v) {
|
||||||
*this = *this - v;
|
*this = *this - v;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::operator+(const SphericalOf<T> &s2) const {
|
SphericalOf<T> SphericalOf<T>::operator+(const SphericalOf<T>& s2) const {
|
||||||
// let's do it the easy way...
|
// let's do it the easy way...
|
||||||
Vector3 v1 = this->ToVector3();
|
Vector3 v1 = this->ToVector3();
|
||||||
Vector3 v2 = s2.ToVector3();
|
Vector3 v2 = s2.ToVector3();
|
||||||
@ -204,17 +211,19 @@ SphericalOf<T> SphericalOf<T>::operator+(const SphericalOf<T> &s2) const {
|
|||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::operator+=(const SphericalOf<T> &v) {
|
SphericalOf<T> SphericalOf<T>::operator+=(const SphericalOf<T>& v) {
|
||||||
*this = *this + v;
|
*this = *this + v;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> SphericalOf<T> SphericalOf<T>::operator*=(float f) {
|
template <typename T>
|
||||||
|
SphericalOf<T> SphericalOf<T>::operator*=(float f) {
|
||||||
this->distance *= f;
|
this->distance *= f;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
template <typename T> SphericalOf<T> SphericalOf<T>::operator/=(float f) {
|
template <typename T>
|
||||||
|
SphericalOf<T> SphericalOf<T>::operator/=(float f) {
|
||||||
this->distance /= f;
|
this->distance /= f;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
@ -225,8 +234,8 @@ template <typename T> SphericalOf<T> SphericalOf<T>::operator/=(float f) {
|
|||||||
const float epsilon = 1E-05f;
|
const float epsilon = 1E-05f;
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
float SphericalOf<T>::DistanceBetween(const SphericalOf<T> &v1,
|
float SphericalOf<T>::DistanceBetween(const SphericalOf<T>& v1,
|
||||||
const SphericalOf<T> &v2) {
|
const SphericalOf<T>& v2) {
|
||||||
// SphericalOf<T> difference = v1 - v2;
|
// SphericalOf<T> difference = v1 - v2;
|
||||||
// return difference.distance;
|
// return difference.distance;
|
||||||
Vector3 vec1 = v1.ToVector3();
|
Vector3 vec1 = v1.ToVector3();
|
||||||
@ -236,8 +245,8 @@ float SphericalOf<T>::DistanceBetween(const SphericalOf<T> &v1,
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> SphericalOf<T>::AngleBetween(const SphericalOf &v1,
|
AngleOf<T> SphericalOf<T>::AngleBetween(const SphericalOf& v1,
|
||||||
const SphericalOf &v2) {
|
const SphericalOf& v2) {
|
||||||
// float denominator = v1.distance * v2.distance;
|
// float denominator = v1.distance * v2.distance;
|
||||||
// if (denominator < epsilon)
|
// if (denominator < epsilon)
|
||||||
// return 0.0f;
|
// return 0.0f;
|
||||||
@ -256,9 +265,9 @@ AngleOf<T> SphericalOf<T>::AngleBetween(const SphericalOf &v1,
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
AngleOf<T> Passer::LinearAlgebra::SphericalOf<T>::SignedAngleBetween(
|
AngleOf<T> SphericalOf<T>::SignedAngleBetween(const SphericalOf<T>& v1,
|
||||||
const SphericalOf<T> &v1, const SphericalOf<T> &v2,
|
const SphericalOf<T>& v2,
|
||||||
const SphericalOf<T> &axis) {
|
const SphericalOf<T>& axis) {
|
||||||
Vector3 v1_vector = v1.ToVector3();
|
Vector3 v1_vector = v1.ToVector3();
|
||||||
Vector3 v2_vector = v2.ToVector3();
|
Vector3 v2_vector = v2.ToVector3();
|
||||||
Vector3 axis_vector = axis.ToVector3();
|
Vector3 axis_vector = axis.ToVector3();
|
||||||
@ -267,7 +276,7 @@ AngleOf<T> Passer::LinearAlgebra::SphericalOf<T>::SignedAngleBetween(
|
|||||||
}
|
}
|
||||||
|
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::Rotate(const SphericalOf<T> &v,
|
SphericalOf<T> SphericalOf<T>::Rotate(const SphericalOf<T>& v,
|
||||||
AngleOf<T> horizontalAngle,
|
AngleOf<T> horizontalAngle,
|
||||||
AngleOf<T> verticalAngle) {
|
AngleOf<T> verticalAngle) {
|
||||||
SphericalOf<T> r =
|
SphericalOf<T> r =
|
||||||
@ -276,19 +285,19 @@ SphericalOf<T> SphericalOf<T>::Rotate(const SphericalOf<T> &v,
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::RotateHorizontal(const SphericalOf<T> &v,
|
SphericalOf<T> SphericalOf<T>::RotateHorizontal(const SphericalOf<T>& v,
|
||||||
AngleOf<T> a) {
|
AngleOf<T> a) {
|
||||||
SphericalOf<T> r =
|
SphericalOf<T> r =
|
||||||
SphericalOf(v.distance, v.direction.horizontal + a, v.direction.vertical);
|
SphericalOf(v.distance, v.direction.horizontal + a, v.direction.vertical);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
template <typename T>
|
template <typename T>
|
||||||
SphericalOf<T> SphericalOf<T>::RotateVertical(const SphericalOf<T> &v,
|
SphericalOf<T> SphericalOf<T>::RotateVertical(const SphericalOf<T>& v,
|
||||||
AngleOf<T> a) {
|
AngleOf<T> a) {
|
||||||
SphericalOf<T> r =
|
SphericalOf<T> r =
|
||||||
SphericalOf(v.distance, v.direction.horizontal, v.direction.vertical + a);
|
SphericalOf(v.distance, v.direction.horizontal, v.direction.vertical + a);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
template class Passer::LinearAlgebra::SphericalOf<float>;
|
template class SphericalOf<float>;
|
||||||
template class Passer::LinearAlgebra::SphericalOf<signed short>;
|
template class SphericalOf<signed short>;
|
||||||
|
@ -7,16 +7,17 @@
|
|||||||
|
|
||||||
#include "Direction.h"
|
#include "Direction.h"
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
struct Vector3;
|
struct Vector3;
|
||||||
template <typename T> class PolarOf;
|
template <typename T>
|
||||||
|
class PolarOf;
|
||||||
|
|
||||||
/// @brief A spherical vector using angles in various representations
|
/// @brief A spherical vector using angles in various representations
|
||||||
/// @tparam T The implementation type used for the representations of the agles
|
/// @tparam T The implementation type used for the representations of the agles
|
||||||
template <typename T> class SphericalOf {
|
template <typename T>
|
||||||
public:
|
class SphericalOf {
|
||||||
|
public:
|
||||||
/// @brief The distance in meters
|
/// @brief The distance in meters
|
||||||
/// @remark The distance should never be negative
|
/// @remark The distance should never be negative
|
||||||
float distance;
|
float distance;
|
||||||
@ -38,7 +39,8 @@ public:
|
|||||||
/// @param horizontal The horizontal angle in degrees
|
/// @param horizontal The horizontal angle in degrees
|
||||||
/// @param vertical The vertical angle in degrees
|
/// @param vertical The vertical angle in degrees
|
||||||
/// @return The spherical vector
|
/// @return The spherical vector
|
||||||
static SphericalOf<T> Degrees(float distance, float horizontal,
|
static SphericalOf<T> Degrees(float distance,
|
||||||
|
float horizontal,
|
||||||
float vertical);
|
float vertical);
|
||||||
/// @brief Short-hand Deg alias for the Degrees function
|
/// @brief Short-hand Deg alias for the Degrees function
|
||||||
constexpr static auto Deg = Degrees;
|
constexpr static auto Deg = Degrees;
|
||||||
@ -48,7 +50,8 @@ public:
|
|||||||
/// @param horizontal The horizontal angle in radians
|
/// @param horizontal The horizontal angle in radians
|
||||||
/// @param vertical The vertical angle in radians
|
/// @param vertical The vertical angle in radians
|
||||||
/// @return The spherical vectpr
|
/// @return The spherical vectpr
|
||||||
static SphericalOf<T> Radians(float distance, float horizontal,
|
static SphericalOf<T> Radians(float distance,
|
||||||
|
float horizontal,
|
||||||
float vertical);
|
float vertical);
|
||||||
// Short-hand Rad alias for the Radians function
|
// Short-hand Rad alias for the Radians function
|
||||||
constexpr static auto Rad = Radians;
|
constexpr static auto Rad = Radians;
|
||||||
@ -95,23 +98,23 @@ public:
|
|||||||
/// @brief Subtract a spherical vector from this vector
|
/// @brief Subtract a spherical vector from this vector
|
||||||
/// @param v The vector to subtract
|
/// @param v The vector to subtract
|
||||||
/// @return The result of the subtraction
|
/// @return The result of the subtraction
|
||||||
SphericalOf<T> operator-(const SphericalOf<T> &v) const;
|
SphericalOf<T> operator-(const SphericalOf<T>& v) const;
|
||||||
SphericalOf<T> operator-=(const SphericalOf<T> &v);
|
SphericalOf<T> operator-=(const SphericalOf<T>& v);
|
||||||
/// @brief Add a spherical vector to this vector
|
/// @brief Add a spherical vector to this vector
|
||||||
/// @param v The vector to add
|
/// @param v The vector to add
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
SphericalOf<T> operator+(const SphericalOf<T> &v) const;
|
SphericalOf<T> operator+(const SphericalOf<T>& v) const;
|
||||||
SphericalOf<T> operator+=(const SphericalOf<T> &v);
|
SphericalOf<T> operator+=(const SphericalOf<T>& v);
|
||||||
|
|
||||||
/// @brief Scale the vector uniformly up
|
/// @brief Scale the vector uniformly up
|
||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark This operation will scale the distance of the vector. The angle
|
/// @remark This operation will scale the distance of the vector. The angle
|
||||||
/// will be unaffected.
|
/// will be unaffected.
|
||||||
friend SphericalOf<T> operator*(const SphericalOf<T> &v, float f) {
|
friend SphericalOf<T> operator*(const SphericalOf<T>& v, float f) {
|
||||||
return SphericalOf<T>(v.distance * f, v.direction);
|
return SphericalOf<T>(v.distance * f, v.direction);
|
||||||
}
|
}
|
||||||
friend SphericalOf<T> operator*(float f, const SphericalOf<T> &v) {
|
friend SphericalOf<T> operator*(float f, const SphericalOf<T>& v) {
|
||||||
return SphericalOf<T>(f * v.distance, v.direction);
|
return SphericalOf<T>(f * v.distance, v.direction);
|
||||||
}
|
}
|
||||||
SphericalOf<T> operator*=(float f);
|
SphericalOf<T> operator*=(float f);
|
||||||
@ -120,10 +123,10 @@ public:
|
|||||||
/// @return The scaled factor
|
/// @return The scaled factor
|
||||||
/// @remark This operation will scale the distance of the vector. The angle
|
/// @remark This operation will scale the distance of the vector. The angle
|
||||||
/// will be unaffected.
|
/// will be unaffected.
|
||||||
friend SphericalOf<T> operator/(const SphericalOf<T> &v, float f) {
|
friend SphericalOf<T> operator/(const SphericalOf<T>& v, float f) {
|
||||||
return SphericalOf<T>(v.distance / f, v.direction);
|
return SphericalOf<T>(v.distance / f, v.direction);
|
||||||
}
|
}
|
||||||
friend SphericalOf<T> operator/(float f, const SphericalOf<T> &v) {
|
friend SphericalOf<T> operator/(float f, const SphericalOf<T>& v) {
|
||||||
return SphericalOf<T>(f / v.distance, v.direction);
|
return SphericalOf<T>(f / v.distance, v.direction);
|
||||||
}
|
}
|
||||||
SphericalOf<T> operator/=(float f);
|
SphericalOf<T> operator/=(float f);
|
||||||
@ -132,41 +135,42 @@ public:
|
|||||||
/// @param v1 The first coordinate
|
/// @param v1 The first coordinate
|
||||||
/// @param v2 The second coordinate
|
/// @param v2 The second coordinate
|
||||||
/// @return The distance between the coordinates in meters
|
/// @return The distance between the coordinates in meters
|
||||||
static float DistanceBetween(const SphericalOf<T> &v1,
|
static float DistanceBetween(const SphericalOf<T>& v1,
|
||||||
const SphericalOf<T> &v2);
|
const SphericalOf<T>& v2);
|
||||||
/// @brief Calculate the unsigned angle between two spherical vectors
|
/// @brief Calculate the unsigned angle between two spherical vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The unsigned angle between the vectors
|
/// @return The unsigned angle between the vectors
|
||||||
static AngleOf<T> AngleBetween(const SphericalOf<T> &v1,
|
static AngleOf<T> AngleBetween(const SphericalOf<T>& v1,
|
||||||
const SphericalOf<T> &v2);
|
const SphericalOf<T>& v2);
|
||||||
/// @brief Calculate the signed angle between two spherical vectors
|
/// @brief Calculate the signed angle between two spherical vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @param axis The axis are which the angle is calculated
|
/// @param axis The axis are which the angle is calculated
|
||||||
/// @return The signed angle between the vectors
|
/// @return The signed angle between the vectors
|
||||||
static AngleOf<T> SignedAngleBetween(const SphericalOf<T> &v1,
|
static AngleOf<T> SignedAngleBetween(const SphericalOf<T>& v1,
|
||||||
const SphericalOf<T> &v2,
|
const SphericalOf<T>& v2,
|
||||||
const SphericalOf<T> &axis);
|
const SphericalOf<T>& axis);
|
||||||
|
|
||||||
/// @brief Rotate a spherical vector
|
/// @brief Rotate a spherical vector
|
||||||
/// @param v The vector to rotate
|
/// @param v The vector to rotate
|
||||||
/// @param horizontalAngle The horizontal rotation angle in local space
|
/// @param horizontalAngle The horizontal rotation angle in local space
|
||||||
/// @param verticalAngle The vertical rotation angle in local space
|
/// @param verticalAngle The vertical rotation angle in local space
|
||||||
/// @return The rotated vector
|
/// @return The rotated vector
|
||||||
static SphericalOf<T> Rotate(const SphericalOf &v, AngleOf<T> horizontalAngle,
|
static SphericalOf<T> Rotate(const SphericalOf& v,
|
||||||
|
AngleOf<T> horizontalAngle,
|
||||||
AngleOf<T> verticalAngle);
|
AngleOf<T> verticalAngle);
|
||||||
/// @brief Rotate a spherical vector horizontally
|
/// @brief Rotate a spherical vector horizontally
|
||||||
/// @param v The vector to rotate
|
/// @param v The vector to rotate
|
||||||
/// @param angle The horizontal rotation angle in local space
|
/// @param angle The horizontal rotation angle in local space
|
||||||
/// @return The rotated vector
|
/// @return The rotated vector
|
||||||
static SphericalOf<T> RotateHorizontal(const SphericalOf<T> &v,
|
static SphericalOf<T> RotateHorizontal(const SphericalOf<T>& v,
|
||||||
AngleOf<T> angle);
|
AngleOf<T> angle);
|
||||||
/// @brief Rotate a spherical vector vertically
|
/// @brief Rotate a spherical vector vertically
|
||||||
/// @param v The vector to rotate
|
/// @param v The vector to rotate
|
||||||
/// @param angle The vertical rotation angle in local space
|
/// @param angle The vertical rotation angle in local space
|
||||||
/// @return The rotated vector
|
/// @return The rotated vector
|
||||||
static SphericalOf<T> RotateVertical(const SphericalOf<T> &v,
|
static SphericalOf<T> RotateVertical(const SphericalOf<T>& v,
|
||||||
AngleOf<T> angle);
|
AngleOf<T> angle);
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -186,9 +190,8 @@ using Spherical = Spherical16;
|
|||||||
using Spherical = SphericalSingle;
|
using Spherical = SphericalSingle;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#include "Polar.h"
|
#include "Polar.h"
|
||||||
#include "Vector3.h"
|
#include "Vector3.h"
|
||||||
|
@ -164,5 +164,5 @@ void SwingTwistOf<T>::Normalize() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
template class Passer::LinearAlgebra::SwingTwistOf<float>;
|
template class SwingTwistOf<float>;
|
||||||
template class Passer::LinearAlgebra::SwingTwistOf<signed short>;
|
template class SwingTwistOf<signed short>;
|
@ -10,14 +10,14 @@
|
|||||||
#include "Quaternion.h"
|
#include "Quaternion.h"
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
/// @brief An orientation using swing and twist angles in various
|
/// @brief An orientation using swing and twist angles in various
|
||||||
/// representations
|
/// representations
|
||||||
/// @tparam T The implmentation type used for the representation of the angles
|
/// @tparam T The implmentation type used for the representation of the angles
|
||||||
template <typename T> class SwingTwistOf {
|
template <typename T>
|
||||||
public:
|
class SwingTwistOf {
|
||||||
|
public:
|
||||||
DirectionOf<T> swing;
|
DirectionOf<T> swing;
|
||||||
AngleOf<T> twist;
|
AngleOf<T> twist;
|
||||||
|
|
||||||
@ -25,7 +25,8 @@ public:
|
|||||||
SwingTwistOf<T>(DirectionOf<T> swing, AngleOf<T> twist);
|
SwingTwistOf<T>(DirectionOf<T> swing, AngleOf<T> twist);
|
||||||
SwingTwistOf<T>(AngleOf<T> horizontal, AngleOf<T> vertical, AngleOf<T> twist);
|
SwingTwistOf<T>(AngleOf<T> horizontal, AngleOf<T> vertical, AngleOf<T> twist);
|
||||||
|
|
||||||
static SwingTwistOf<T> Degrees(float horizontal, float vertical = 0,
|
static SwingTwistOf<T> Degrees(float horizontal,
|
||||||
|
float vertical = 0,
|
||||||
float twist = 0);
|
float twist = 0);
|
||||||
|
|
||||||
Quaternion ToQuaternion() const;
|
Quaternion ToQuaternion() const;
|
||||||
@ -43,7 +44,7 @@ public:
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="vector">The vector to rotate</param>
|
/// <param name="vector">The vector to rotate</param>
|
||||||
/// <returns>The rotated vector</returns>
|
/// <returns>The rotated vector</returns>
|
||||||
SphericalOf<T> operator*(const SphericalOf<T> &vector) const;
|
SphericalOf<T> operator*(const SphericalOf<T>& vector) const;
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Multiply this rotation with another rotation
|
/// Multiply this rotation with another rotation
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -51,8 +52,8 @@ public:
|
|||||||
/// <returns>The resulting swing/twist rotation</returns>
|
/// <returns>The resulting swing/twist rotation</returns>
|
||||||
/// The result will be this rotation rotated according to
|
/// The result will be this rotation rotated according to
|
||||||
/// the give rotation.
|
/// the give rotation.
|
||||||
SwingTwistOf<T> operator*(const SwingTwistOf<T> &rotation) const;
|
SwingTwistOf<T> operator*(const SwingTwistOf<T>& rotation) const;
|
||||||
SwingTwistOf<T> operator*=(const SwingTwistOf<T> &rotation);
|
SwingTwistOf<T> operator*=(const SwingTwistOf<T>& rotation);
|
||||||
|
|
||||||
static SwingTwistOf<T> Inverse(SwingTwistOf<T> rotation);
|
static SwingTwistOf<T> Inverse(SwingTwistOf<T> rotation);
|
||||||
|
|
||||||
@ -62,9 +63,9 @@ public:
|
|||||||
/// <param name="angle">The angle</param>
|
/// <param name="angle">The angle</param>
|
||||||
/// <param name="axis">The axis</param>
|
/// <param name="axis">The axis</param>
|
||||||
/// <returns>The resulting quaternion</returns>
|
/// <returns>The resulting quaternion</returns>
|
||||||
static SwingTwistOf<T> AngleAxis(float angle, const DirectionOf<T> &axis);
|
static SwingTwistOf<T> AngleAxis(float angle, const DirectionOf<T>& axis);
|
||||||
|
|
||||||
static AngleOf<T> Angle(const SwingTwistOf<T> &r1, const SwingTwistOf<T> &r2);
|
static AngleOf<T> Angle(const SwingTwistOf<T>& r1, const SwingTwistOf<T>& r2);
|
||||||
|
|
||||||
void Normalize();
|
void Normalize();
|
||||||
};
|
};
|
||||||
@ -72,8 +73,13 @@ public:
|
|||||||
using SwingTwistSingle = SwingTwistOf<float>;
|
using SwingTwistSingle = SwingTwistOf<float>;
|
||||||
using SwingTwist16 = SwingTwistOf<signed short>;
|
using SwingTwist16 = SwingTwistOf<signed short>;
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
#if defined(ARDUINO)
|
||||||
} // namespace Passer
|
using SwingTwist = SwingTwist16;
|
||||||
using namespace Passer::LinearAlgebra;
|
#else
|
||||||
|
using SwingTwist = SwingTwistSingle;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
} // namespace LinearAlgebra
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -26,11 +26,11 @@ Vector2::Vector2(float _x, float _y) {
|
|||||||
// y = v.y;
|
// y = v.y;
|
||||||
// }
|
// }
|
||||||
Vector2::Vector2(Vector3 v) {
|
Vector2::Vector2(Vector3 v) {
|
||||||
x = v.Right(); // x;
|
x = v.Right(); // x;
|
||||||
y = v.Forward(); // z;
|
y = v.Forward(); // z;
|
||||||
}
|
}
|
||||||
Vector2::Vector2(PolarSingle p) {
|
Vector2::Vector2(PolarSingle p) {
|
||||||
float horizontalRad = p.angle.InDegrees() * Passer::LinearAlgebra::Deg2Rad;
|
float horizontalRad = p.angle.InDegrees() * Deg2Rad;
|
||||||
float cosHorizontal = cosf(horizontalRad);
|
float cosHorizontal = cosf(horizontalRad);
|
||||||
float sinHorizontal = sinf(horizontalRad);
|
float sinHorizontal = sinf(horizontalRad);
|
||||||
|
|
||||||
@ -49,18 +49,24 @@ const Vector2 Vector2::down = Vector2(0, -1);
|
|||||||
const Vector2 Vector2::forward = Vector2(0, 1);
|
const Vector2 Vector2::forward = Vector2(0, 1);
|
||||||
const Vector2 Vector2::back = Vector2(0, -1);
|
const Vector2 Vector2::back = Vector2(0, -1);
|
||||||
|
|
||||||
bool Vector2::operator==(const Vector2 &v) {
|
bool Vector2::operator==(const Vector2& v) {
|
||||||
return (this->x == v.x && this->y == v.y);
|
return (this->x == v.x && this->y == v.y);
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector2::Magnitude(const Vector2 &v) {
|
float Vector2::Magnitude(const Vector2& v) {
|
||||||
return sqrtf(v.x * v.x + v.y * v.y);
|
return sqrtf(v.x * v.x + v.y * v.y);
|
||||||
}
|
}
|
||||||
float Vector2::magnitude() const { return (float)sqrtf(x * x + y * y); }
|
float Vector2::magnitude() const {
|
||||||
float Vector2::SqrMagnitude(const Vector2 &v) { return v.x * v.x + v.y * v.y; }
|
return (float)sqrtf(x * x + y * y);
|
||||||
float Vector2::sqrMagnitude() const { return (x * x + y * y); }
|
}
|
||||||
|
float Vector2::SqrMagnitude(const Vector2& v) {
|
||||||
|
return v.x * v.x + v.y * v.y;
|
||||||
|
}
|
||||||
|
float Vector2::sqrMagnitude() const {
|
||||||
|
return (x * x + y * y);
|
||||||
|
}
|
||||||
|
|
||||||
Vector2 Vector2::Normalize(const Vector2 &v) {
|
Vector2 Vector2::Normalize(const Vector2& v) {
|
||||||
float num = Vector2::Magnitude(v);
|
float num = Vector2::Magnitude(v);
|
||||||
Vector2 result = Vector2::zero;
|
Vector2 result = Vector2::zero;
|
||||||
if (num > Float::epsilon) {
|
if (num > Float::epsilon) {
|
||||||
@ -77,26 +83,28 @@ Vector2 Vector2::normalized() const {
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector2 Vector2::operator-() { return Vector2(-this->x, -this->y); }
|
Vector2 Vector2::operator-() {
|
||||||
|
return Vector2(-this->x, -this->y);
|
||||||
|
}
|
||||||
|
|
||||||
Vector2 Vector2::operator-(const Vector2 &v) const {
|
Vector2 Vector2::operator-(const Vector2& v) const {
|
||||||
return Vector2(this->x - v.x, this->y - v.y);
|
return Vector2(this->x - v.x, this->y - v.y);
|
||||||
}
|
}
|
||||||
Vector2 Vector2::operator-=(const Vector2 &v) {
|
Vector2 Vector2::operator-=(const Vector2& v) {
|
||||||
this->x -= v.x;
|
this->x -= v.x;
|
||||||
this->y -= v.y;
|
this->y -= v.y;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
Vector2 Vector2::operator+(const Vector2 &v) const {
|
Vector2 Vector2::operator+(const Vector2& v) const {
|
||||||
return Vector2(this->x + v.x, this->y + v.y);
|
return Vector2(this->x + v.x, this->y + v.y);
|
||||||
}
|
}
|
||||||
Vector2 Vector2::operator+=(const Vector2 &v) {
|
Vector2 Vector2::operator+=(const Vector2& v) {
|
||||||
this->x += v.x;
|
this->x += v.x;
|
||||||
this->y += v.y;
|
this->y += v.y;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector2 Vector2::Scale(const Vector2 &v1, const Vector2 &v2) {
|
Vector2 Vector2::Scale(const Vector2& v1, const Vector2& v2) {
|
||||||
return Vector2(v1.x * v2.x, v1.y * v2.y);
|
return Vector2(v1.x * v2.x, v1.y * v2.y);
|
||||||
}
|
}
|
||||||
// Vector2 Passer::LinearAlgebra::operator*(const Vector2 &v, float f) {
|
// Vector2 Passer::LinearAlgebra::operator*(const Vector2 &v, float f) {
|
||||||
@ -122,18 +130,18 @@ Vector2 Vector2::operator/=(float f) {
|
|||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector2::Dot(const Vector2 &v1, const Vector2 &v2) {
|
float Vector2::Dot(const Vector2& v1, const Vector2& v2) {
|
||||||
return v1.x * v2.x + v1.y * v2.y;
|
return v1.x * v2.x + v1.y * v2.y;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector2::Distance(const Vector2 &v1, const Vector2 &v2) {
|
float Vector2::Distance(const Vector2& v1, const Vector2& v2) {
|
||||||
return Magnitude(v1 - v2);
|
return Magnitude(v1 - v2);
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector2::Angle(const Vector2 &v1, const Vector2 &v2) {
|
float Vector2::Angle(const Vector2& v1, const Vector2& v2) {
|
||||||
return (float)fabs(SignedAngle(v1, v2));
|
return (float)fabs(SignedAngle(v1, v2));
|
||||||
}
|
}
|
||||||
float Vector2::SignedAngle(const Vector2 &v1, const Vector2 &v2) {
|
float Vector2::SignedAngle(const Vector2& v1, const Vector2& v2) {
|
||||||
float sqrMagFrom = v1.sqrMagnitude();
|
float sqrMagFrom = v1.sqrMagnitude();
|
||||||
float sqrMagTo = v2.sqrMagnitude();
|
float sqrMagTo = v2.sqrMagnitude();
|
||||||
|
|
||||||
@ -148,15 +156,14 @@ float Vector2::SignedAngle(const Vector2 &v1, const Vector2 &v2) {
|
|||||||
|
|
||||||
float angleFrom = atan2f(v1.y, v1.x);
|
float angleFrom = atan2f(v1.y, v1.x);
|
||||||
float angleTo = atan2f(v2.y, v2.x);
|
float angleTo = atan2f(v2.y, v2.x);
|
||||||
return -(angleTo - angleFrom) * Passer::LinearAlgebra::Rad2Deg;
|
return -(angleTo - angleFrom) * Rad2Deg;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector2 Vector2::Rotate(const Vector2 &v,
|
Vector2 Vector2::Rotate(const Vector2& v, AngleSingle a) {
|
||||||
Passer::LinearAlgebra::AngleSingle a) {
|
float angleRad = a.InDegrees() * Deg2Rad;
|
||||||
float angleRad = a.InDegrees() * Passer::LinearAlgebra::Deg2Rad;
|
|
||||||
#if defined(AVR)
|
#if defined(AVR)
|
||||||
float sinValue = sin(angleRad);
|
float sinValue = sin(angleRad);
|
||||||
float cosValue = cos(angleRad); // * Angle::Deg2Rad);
|
float cosValue = cos(angleRad); // * Angle::Deg2Rad);
|
||||||
#else
|
#else
|
||||||
float sinValue = (float)sinf(angleRad);
|
float sinValue = (float)sinf(angleRad);
|
||||||
float cosValue = (float)cosf(angleRad);
|
float cosValue = (float)cosf(angleRad);
|
||||||
@ -169,7 +176,7 @@ Vector2 Vector2::Rotate(const Vector2 &v,
|
|||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector2 Vector2::Lerp(const Vector2 &v1, const Vector2 &v2, float f) {
|
Vector2 Vector2::Lerp(const Vector2& v1, const Vector2& v2, float f) {
|
||||||
Vector2 v = v1 + (v2 - v1) * f;
|
Vector2 v = v1 + (v2 - v1) * f;
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
@ -26,11 +26,11 @@ typedef struct Vec2 {
|
|||||||
} Vec2;
|
} Vec2;
|
||||||
}
|
}
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
struct Vector3;
|
struct Vector3;
|
||||||
template <typename T> class PolarOf;
|
template <typename T>
|
||||||
|
class PolarOf;
|
||||||
|
|
||||||
/// @brief A 2-dimensional vector
|
/// @brief A 2-dimensional vector
|
||||||
/// @remark This uses the right=handed carthesian coordinate system.
|
/// @remark This uses the right=handed carthesian coordinate system.
|
||||||
@ -38,7 +38,7 @@ template <typename T> class PolarOf;
|
|||||||
struct Vector2 : Vec2 {
|
struct Vector2 : Vec2 {
|
||||||
friend struct Vec2;
|
friend struct Vec2;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief A new 2-dimensional zero vector
|
/// @brief A new 2-dimensional zero vector
|
||||||
Vector2();
|
Vector2();
|
||||||
/// @brief A new 2-dimensional vector
|
/// @brief A new 2-dimensional vector
|
||||||
@ -80,12 +80,12 @@ public:
|
|||||||
/// @return true if it is identical to the given vector
|
/// @return true if it is identical to the given vector
|
||||||
/// @note This uses float comparison to check equality which may have strange
|
/// @note This uses float comparison to check equality which may have strange
|
||||||
/// effects. Equality on floats should be avoided.
|
/// effects. Equality on floats should be avoided.
|
||||||
bool operator==(const Vector2 &v);
|
bool operator==(const Vector2& v);
|
||||||
|
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @param v The vector for which you need the length
|
/// @param v The vector for which you need the length
|
||||||
/// @return The vector length
|
/// @return The vector length
|
||||||
static float Magnitude(const Vector2 &v);
|
static float Magnitude(const Vector2& v);
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @return The vector length
|
/// @return The vector length
|
||||||
float magnitude() const;
|
float magnitude() const;
|
||||||
@ -95,7 +95,7 @@ public:
|
|||||||
/// @remark The squared length is computationally simpler than the real
|
/// @remark The squared length is computationally simpler than the real
|
||||||
/// length. Think of Pythagoras A^2 + B^2 = C^2. This prevents the calculation
|
/// length. Think of Pythagoras A^2 + B^2 = C^2. This prevents the calculation
|
||||||
/// of the squared root of C.
|
/// of the squared root of C.
|
||||||
static float SqrMagnitude(const Vector2 &v);
|
static float SqrMagnitude(const Vector2& v);
|
||||||
/// @brief The squared vector length
|
/// @brief The squared vector length
|
||||||
/// @return The squared vector length
|
/// @return The squared vector length
|
||||||
/// @remark The squared length is computationally simpler than the real
|
/// @remark The squared length is computationally simpler than the real
|
||||||
@ -106,7 +106,7 @@ public:
|
|||||||
/// @brief Convert the vector to a length of 1
|
/// @brief Convert the vector to a length of 1
|
||||||
/// @param v The vector to convert
|
/// @param v The vector to convert
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
static Vector2 Normalize(const Vector2 &v);
|
static Vector2 Normalize(const Vector2& v);
|
||||||
/// @brief Convert the vector to a length 1
|
/// @brief Convert the vector to a length 1
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
Vector2 normalized() const;
|
Vector2 normalized() const;
|
||||||
@ -118,13 +118,13 @@ public:
|
|||||||
/// @brief Subtract a vector from this vector
|
/// @brief Subtract a vector from this vector
|
||||||
/// @param v The vector to subtract from this vector
|
/// @param v The vector to subtract from this vector
|
||||||
/// @return The result of the subtraction
|
/// @return The result of the subtraction
|
||||||
Vector2 operator-(const Vector2 &v) const;
|
Vector2 operator-(const Vector2& v) const;
|
||||||
Vector2 operator-=(const Vector2 &v);
|
Vector2 operator-=(const Vector2& v);
|
||||||
/// @brief Add a vector to this vector
|
/// @brief Add a vector to this vector
|
||||||
/// @param v The vector to add to this vector
|
/// @param v The vector to add to this vector
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
Vector2 operator+(const Vector2 &v) const;
|
Vector2 operator+(const Vector2& v) const;
|
||||||
Vector2 operator+=(const Vector2 &v);
|
Vector2 operator+=(const Vector2& v);
|
||||||
|
|
||||||
/// @brief Scale the vector using another vector
|
/// @brief Scale the vector using another vector
|
||||||
/// @param v1 The vector to scale
|
/// @param v1 The vector to scale
|
||||||
@ -132,16 +132,16 @@ public:
|
|||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each component of the vector v1 will be multiplied with the
|
/// @remark Each component of the vector v1 will be multiplied with the
|
||||||
/// matching component from the scaling vector v2.
|
/// matching component from the scaling vector v2.
|
||||||
static Vector2 Scale(const Vector2 &v1, const Vector2 &v2);
|
static Vector2 Scale(const Vector2& v1, const Vector2& v2);
|
||||||
/// @brief Scale the vector uniformly up
|
/// @brief Scale the vector uniformly up
|
||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each component of the vector will be multipled with the same
|
/// @remark Each component of the vector will be multipled with the same
|
||||||
/// factor f.
|
/// factor f.
|
||||||
friend Vector2 operator*(const Vector2 &v, float f) {
|
friend Vector2 operator*(const Vector2& v, float f) {
|
||||||
return Vector2(v.x * f, v.y * f);
|
return Vector2(v.x * f, v.y * f);
|
||||||
}
|
}
|
||||||
friend Vector2 operator*(float f, const Vector2 &v) {
|
friend Vector2 operator*(float f, const Vector2& v) {
|
||||||
return Vector2(v.x * f, v.y * f);
|
return Vector2(v.x * f, v.y * f);
|
||||||
// return Vector2(f * v.x, f * v.y);
|
// return Vector2(f * v.x, f * v.y);
|
||||||
}
|
}
|
||||||
@ -150,10 +150,10 @@ public:
|
|||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each componet of the vector will be divided by the same factor.
|
/// @remark Each componet of the vector will be divided by the same factor.
|
||||||
friend Vector2 operator/(const Vector2 &v, float f) {
|
friend Vector2 operator/(const Vector2& v, float f) {
|
||||||
return Vector2(v.x / f, v.y / f);
|
return Vector2(v.x / f, v.y / f);
|
||||||
}
|
}
|
||||||
friend Vector2 operator/(float f, const Vector2 &v) {
|
friend Vector2 operator/(float f, const Vector2& v) {
|
||||||
return Vector2(f / v.x, f / v.y);
|
return Vector2(f / v.x, f / v.y);
|
||||||
}
|
}
|
||||||
Vector2 operator/=(float f);
|
Vector2 operator/=(float f);
|
||||||
@ -162,13 +162,13 @@ public:
|
|||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The dot product of the two vectors
|
/// @return The dot product of the two vectors
|
||||||
static float Dot(const Vector2 &v1, const Vector2 &v2);
|
static float Dot(const Vector2& v1, const Vector2& v2);
|
||||||
|
|
||||||
/// @brief The distance between two vectors
|
/// @brief The distance between two vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The distance between the two vectors
|
/// @return The distance between the two vectors
|
||||||
static float Distance(const Vector2 &v1, const Vector2 &v2);
|
static float Distance(const Vector2& v1, const Vector2& v2);
|
||||||
|
|
||||||
/// @brief The angle between two vectors
|
/// @brief The angle between two vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
@ -177,18 +177,18 @@ public:
|
|||||||
/// @remark This reterns an unsigned angle which is the shortest distance
|
/// @remark This reterns an unsigned angle which is the shortest distance
|
||||||
/// between the two vectors. Use Vector2::SignedAngle if a signed angle is
|
/// between the two vectors. Use Vector2::SignedAngle if a signed angle is
|
||||||
/// needed.
|
/// needed.
|
||||||
static float Angle(const Vector2 &v1, const Vector2 &v2);
|
static float Angle(const Vector2& v1, const Vector2& v2);
|
||||||
/// @brief The signed angle between two vectors
|
/// @brief The signed angle between two vectors
|
||||||
/// @param v1 The starting vector
|
/// @param v1 The starting vector
|
||||||
/// @param v2 The ending vector
|
/// @param v2 The ending vector
|
||||||
/// @return The signed angle between the two vectors
|
/// @return The signed angle between the two vectors
|
||||||
static float SignedAngle(const Vector2 &v1, const Vector2 &v2);
|
static float SignedAngle(const Vector2& v1, const Vector2& v2);
|
||||||
|
|
||||||
/// @brief Rotate the vector
|
/// @brief Rotate the vector
|
||||||
/// @param v The vector to rotate
|
/// @param v The vector to rotate
|
||||||
/// @param a The angle in degrees to rotate
|
/// @param a The angle in degrees to rotate
|
||||||
/// @return The rotated vector
|
/// @return The rotated vector
|
||||||
static Vector2 Rotate(const Vector2 &v, Passer::LinearAlgebra::AngleSingle a);
|
static Vector2 Rotate(const Vector2& v, AngleSingle a);
|
||||||
|
|
||||||
/// @brief Lerp (linear interpolation) between two vectors
|
/// @brief Lerp (linear interpolation) between two vectors
|
||||||
/// @param v1 The starting vector
|
/// @param v1 The starting vector
|
||||||
@ -198,12 +198,11 @@ public:
|
|||||||
/// @remark The factor f is unclamped. Value 0 matches the vector *v1*, Value
|
/// @remark The factor f is unclamped. Value 0 matches the vector *v1*, Value
|
||||||
/// 1 matches vector *v2*. Value -1 is vector *v1* minus the difference
|
/// 1 matches vector *v2*. Value -1 is vector *v1* minus the difference
|
||||||
/// between *v1* and *v2* etc.
|
/// between *v1* and *v2* etc.
|
||||||
static Vector2 Lerp(const Vector2 &v1, const Vector2 &v2, float f);
|
static Vector2 Lerp(const Vector2& v1, const Vector2& v2, float f);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#include "Polar.h"
|
#include "Polar.h"
|
||||||
|
|
||||||
|
@ -31,10 +31,8 @@ Vector3::Vector3(Vector2 v) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Vector3::Vector3(SphericalOf<float> s) {
|
Vector3::Vector3(SphericalOf<float> s) {
|
||||||
float verticalRad = (90.0f - s.direction.vertical.InDegrees()) *
|
float verticalRad = (90.0f - s.direction.vertical.InDegrees()) * Deg2Rad;
|
||||||
Passer::LinearAlgebra::Deg2Rad;
|
float horizontalRad = s.direction.horizontal.InDegrees() * Deg2Rad;
|
||||||
float horizontalRad =
|
|
||||||
s.direction.horizontal.InDegrees() * Passer::LinearAlgebra::Deg2Rad;
|
|
||||||
float cosVertical = cosf(verticalRad);
|
float cosVertical = cosf(verticalRad);
|
||||||
float sinVertical = sinf(verticalRad);
|
float sinVertical = sinf(verticalRad);
|
||||||
float cosHorizontal = cosf(horizontalRad);
|
float cosHorizontal = cosf(horizontalRad);
|
||||||
@ -67,17 +65,21 @@ const Vector3 Vector3::back = Vector3(0, 0, -1);
|
|||||||
// return Vector3(v.x, 0, v.y);
|
// return Vector3(v.x, 0, v.y);
|
||||||
// }
|
// }
|
||||||
|
|
||||||
float Vector3::Magnitude(const Vector3 &v) {
|
float Vector3::Magnitude(const Vector3& v) {
|
||||||
return sqrtf(v.x * v.x + v.y * v.y + v.z * v.z);
|
return sqrtf(v.x * v.x + v.y * v.y + v.z * v.z);
|
||||||
}
|
}
|
||||||
float Vector3::magnitude() const { return (float)sqrtf(x * x + y * y + z * z); }
|
float Vector3::magnitude() const {
|
||||||
|
return (float)sqrtf(x * x + y * y + z * z);
|
||||||
|
}
|
||||||
|
|
||||||
float Vector3::SqrMagnitude(const Vector3 &v) {
|
float Vector3::SqrMagnitude(const Vector3& v) {
|
||||||
return v.x * v.x + v.y * v.y + v.z * v.z;
|
return v.x * v.x + v.y * v.y + v.z * v.z;
|
||||||
}
|
}
|
||||||
float Vector3::sqrMagnitude() const { return (x * x + y * y + z * z); }
|
float Vector3::sqrMagnitude() const {
|
||||||
|
return (x * x + y * y + z * z);
|
||||||
|
}
|
||||||
|
|
||||||
Vector3 Vector3::Normalize(const Vector3 &v) {
|
Vector3 Vector3::Normalize(const Vector3& v) {
|
||||||
float num = Vector3::Magnitude(v);
|
float num = Vector3::Magnitude(v);
|
||||||
Vector3 result = Vector3::zero;
|
Vector3 result = Vector3::zero;
|
||||||
if (num > epsilon) {
|
if (num > epsilon) {
|
||||||
@ -98,26 +100,26 @@ Vector3 Vector3::operator-() const {
|
|||||||
return Vector3(-this->x, -this->y, -this->z);
|
return Vector3(-this->x, -this->y, -this->z);
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::operator-(const Vector3 &v) const {
|
Vector3 Vector3::operator-(const Vector3& v) const {
|
||||||
return Vector3(this->x - v.x, this->y - v.y, this->z - v.z);
|
return Vector3(this->x - v.x, this->y - v.y, this->z - v.z);
|
||||||
}
|
}
|
||||||
Vector3 Vector3::operator-=(const Vector3 &v) {
|
Vector3 Vector3::operator-=(const Vector3& v) {
|
||||||
this->x -= v.x;
|
this->x -= v.x;
|
||||||
this->y -= v.y;
|
this->y -= v.y;
|
||||||
this->z -= v.z;
|
this->z -= v.z;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
Vector3 Vector3::operator+(const Vector3 &v) const {
|
Vector3 Vector3::operator+(const Vector3& v) const {
|
||||||
return Vector3(this->x + v.x, this->y + v.y, this->z + v.z);
|
return Vector3(this->x + v.x, this->y + v.y, this->z + v.z);
|
||||||
}
|
}
|
||||||
Vector3 Vector3::operator+=(const Vector3 &v) {
|
Vector3 Vector3::operator+=(const Vector3& v) {
|
||||||
this->x += v.x;
|
this->x += v.x;
|
||||||
this->y += v.y;
|
this->y += v.y;
|
||||||
this->z += v.z;
|
this->z += v.z;
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::Scale(const Vector3 &v1, const Vector3 &v2) {
|
Vector3 Vector3::Scale(const Vector3& v1, const Vector3& v2) {
|
||||||
return Vector3(v1.x * v2.x, v1.y * v2.y, v1.z * v2.z);
|
return Vector3(v1.x * v2.x, v1.y * v2.y, v1.z * v2.z);
|
||||||
}
|
}
|
||||||
// Vector3 Passer::LinearAlgebra::operator*(const Vector3 &v, float f) {
|
// Vector3 Passer::LinearAlgebra::operator*(const Vector3 &v, float f) {
|
||||||
@ -145,24 +147,24 @@ Vector3 Vector3::operator/=(float f) {
|
|||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector3::Dot(const Vector3 &v1, const Vector3 &v2) {
|
float Vector3::Dot(const Vector3& v1, const Vector3& v2) {
|
||||||
return v1.x * v2.x + v1.y * v2.y + v1.z * v2.z;
|
return v1.x * v2.x + v1.y * v2.y + v1.z * v2.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Vector3::operator==(const Vector3 &v) const {
|
bool Vector3::operator==(const Vector3& v) const {
|
||||||
return (this->x == v.x && this->y == v.y && this->z == v.z);
|
return (this->x == v.x && this->y == v.y && this->z == v.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
float Vector3::Distance(const Vector3 &v1, const Vector3 &v2) {
|
float Vector3::Distance(const Vector3& v1, const Vector3& v2) {
|
||||||
return Magnitude(v1 - v2);
|
return Magnitude(v1 - v2);
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::Cross(const Vector3 &v1, const Vector3 &v2) {
|
Vector3 Vector3::Cross(const Vector3& v1, const Vector3& v2) {
|
||||||
return Vector3(v1.y * v2.z - v1.z * v2.y, v1.z * v2.x - v1.x * v2.z,
|
return Vector3(v1.y * v2.z - v1.z * v2.y, v1.z * v2.x - v1.x * v2.z,
|
||||||
v1.x * v2.y - v1.y * v2.x);
|
v1.x * v2.y - v1.y * v2.x);
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::Project(const Vector3 &v, const Vector3 &n) {
|
Vector3 Vector3::Project(const Vector3& v, const Vector3& n) {
|
||||||
float sqrMagnitude = Dot(n, n);
|
float sqrMagnitude = Dot(n, n);
|
||||||
if (sqrMagnitude < epsilon)
|
if (sqrMagnitude < epsilon)
|
||||||
return Vector3::zero;
|
return Vector3::zero;
|
||||||
@ -173,7 +175,7 @@ Vector3 Vector3::Project(const Vector3 &v, const Vector3 &n) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::ProjectOnPlane(const Vector3 &v, const Vector3 &n) {
|
Vector3 Vector3::ProjectOnPlane(const Vector3& v, const Vector3& n) {
|
||||||
Vector3 r = v - Project(v, n);
|
Vector3 r = v - Project(v, n);
|
||||||
return r;
|
return r;
|
||||||
}
|
}
|
||||||
@ -184,7 +186,7 @@ float clamp(float x, float lower, float upper) {
|
|||||||
return upperClamp;
|
return upperClamp;
|
||||||
}
|
}
|
||||||
|
|
||||||
AngleOf<float> Vector3::Angle(const Vector3 &v1, const Vector3 &v2) {
|
AngleOf<float> Vector3::Angle(const Vector3& v1, const Vector3& v2) {
|
||||||
float denominator = sqrtf(v1.sqrMagnitude() * v2.sqrMagnitude());
|
float denominator = sqrtf(v1.sqrMagnitude() * v2.sqrMagnitude());
|
||||||
if (denominator < epsilon)
|
if (denominator < epsilon)
|
||||||
return AngleOf<float>();
|
return AngleOf<float>();
|
||||||
@ -193,15 +195,16 @@ AngleOf<float> Vector3::Angle(const Vector3 &v1, const Vector3 &v2) {
|
|||||||
float fraction = dot / denominator;
|
float fraction = dot / denominator;
|
||||||
if (isnan(fraction))
|
if (isnan(fraction))
|
||||||
return AngleOf<float>::Degrees(
|
return AngleOf<float>::Degrees(
|
||||||
fraction); // short cut to returning NaN universally
|
fraction); // short cut to returning NaN universally
|
||||||
|
|
||||||
float cdot = clamp(fraction, -1.0, 1.0);
|
float cdot = clamp(fraction, -1.0, 1.0);
|
||||||
float r = ((float)acos(cdot));
|
float r = ((float)acos(cdot));
|
||||||
return AngleOf<float>::Radians(r);
|
return AngleOf<float>::Radians(r);
|
||||||
}
|
}
|
||||||
|
|
||||||
AngleOf<float> Vector3::SignedAngle(const Vector3 &v1, const Vector3 &v2,
|
AngleOf<float> Vector3::SignedAngle(const Vector3& v1,
|
||||||
const Vector3 &axis) {
|
const Vector3& v2,
|
||||||
|
const Vector3& axis) {
|
||||||
// angle in [0,180]
|
// angle in [0,180]
|
||||||
AngleOf<float> angle = Vector3::Angle(v1, v2);
|
AngleOf<float> angle = Vector3::Angle(v1, v2);
|
||||||
|
|
||||||
@ -215,7 +218,7 @@ AngleOf<float> Vector3::SignedAngle(const Vector3 &v1, const Vector3 &v2,
|
|||||||
return AngleOf<float>(signed_angle);
|
return AngleOf<float>(signed_angle);
|
||||||
}
|
}
|
||||||
|
|
||||||
Vector3 Vector3::Lerp(const Vector3 &v1, const Vector3 &v2, float f) {
|
Vector3 Vector3::Lerp(const Vector3& v1, const Vector3& v2, float f) {
|
||||||
Vector3 v = v1 + (v2 - v1) * f;
|
Vector3 v = v1 + (v2 - v1) * f;
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
@ -14,7 +14,7 @@ extern "C" {
|
|||||||
/// This is a C-style implementation
|
/// This is a C-style implementation
|
||||||
/// This uses the right-handed coordinate system.
|
/// This uses the right-handed coordinate system.
|
||||||
typedef struct Vec3 {
|
typedef struct Vec3 {
|
||||||
protected:
|
protected:
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// The right axis of the vector
|
/// The right axis of the vector
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -31,10 +31,10 @@ protected:
|
|||||||
} Vec3;
|
} Vec3;
|
||||||
}
|
}
|
||||||
|
|
||||||
namespace Passer {
|
|
||||||
namespace LinearAlgebra {
|
namespace LinearAlgebra {
|
||||||
|
|
||||||
template <typename T> class SphericalOf;
|
template <typename T>
|
||||||
|
class SphericalOf;
|
||||||
|
|
||||||
/// @brief A 3-dimensional vector
|
/// @brief A 3-dimensional vector
|
||||||
/// @remark This uses a right-handed carthesian coordinate system.
|
/// @remark This uses a right-handed carthesian coordinate system.
|
||||||
@ -42,7 +42,7 @@ template <typename T> class SphericalOf;
|
|||||||
struct Vector3 : Vec3 {
|
struct Vector3 : Vec3 {
|
||||||
friend struct Vec3;
|
friend struct Vec3;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief A new 3-dimensional zero vector
|
/// @brief A new 3-dimensional zero vector
|
||||||
Vector3();
|
Vector3();
|
||||||
/// @brief A new 3-dimensional vector
|
/// @brief A new 3-dimensional vector
|
||||||
@ -88,12 +88,12 @@ public:
|
|||||||
/// @return true if it is identical to the given vector
|
/// @return true if it is identical to the given vector
|
||||||
/// @note This uses float comparison to check equality which may have strange
|
/// @note This uses float comparison to check equality which may have strange
|
||||||
/// effects. Equality on floats should be avoided.
|
/// effects. Equality on floats should be avoided.
|
||||||
bool operator==(const Vector3 &v) const;
|
bool operator==(const Vector3& v) const;
|
||||||
|
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @param v The vector for which you need the length
|
/// @param v The vector for which you need the length
|
||||||
/// @return The vector length
|
/// @return The vector length
|
||||||
static float Magnitude(const Vector3 &v);
|
static float Magnitude(const Vector3& v);
|
||||||
/// @brief The vector length
|
/// @brief The vector length
|
||||||
/// @return The vector length
|
/// @return The vector length
|
||||||
float magnitude() const;
|
float magnitude() const;
|
||||||
@ -103,7 +103,7 @@ public:
|
|||||||
/// @remark The squared length is computationally simpler than the real
|
/// @remark The squared length is computationally simpler than the real
|
||||||
/// length. Think of Pythagoras A^2 + B^2 = C^2. This leaves out the
|
/// length. Think of Pythagoras A^2 + B^2 = C^2. This leaves out the
|
||||||
/// calculation of the squared root of C.
|
/// calculation of the squared root of C.
|
||||||
static float SqrMagnitude(const Vector3 &v);
|
static float SqrMagnitude(const Vector3& v);
|
||||||
/// @brief The squared vector length
|
/// @brief The squared vector length
|
||||||
/// @return The squared vector length
|
/// @return The squared vector length
|
||||||
/// @remark The squared length is computationally simpler than the real
|
/// @remark The squared length is computationally simpler than the real
|
||||||
@ -114,7 +114,7 @@ public:
|
|||||||
/// @brief Convert the vector to a length of 1
|
/// @brief Convert the vector to a length of 1
|
||||||
/// @param v The vector to convert
|
/// @param v The vector to convert
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
static Vector3 Normalize(const Vector3 &v);
|
static Vector3 Normalize(const Vector3& v);
|
||||||
/// @brief Convert the vector to a length of 1
|
/// @brief Convert the vector to a length of 1
|
||||||
/// @return The vector normalized to a length of 1
|
/// @return The vector normalized to a length of 1
|
||||||
Vector3 normalized() const;
|
Vector3 normalized() const;
|
||||||
@ -126,13 +126,13 @@ public:
|
|||||||
/// @brief Subtract a vector from this vector
|
/// @brief Subtract a vector from this vector
|
||||||
/// @param v The vector to subtract from this vector
|
/// @param v The vector to subtract from this vector
|
||||||
/// @return The result of this subtraction
|
/// @return The result of this subtraction
|
||||||
Vector3 operator-(const Vector3 &v) const;
|
Vector3 operator-(const Vector3& v) const;
|
||||||
Vector3 operator-=(const Vector3 &v);
|
Vector3 operator-=(const Vector3& v);
|
||||||
/// @brief Add a vector to this vector
|
/// @brief Add a vector to this vector
|
||||||
/// @param v The vector to add to this vector
|
/// @param v The vector to add to this vector
|
||||||
/// @return The result of the addition
|
/// @return The result of the addition
|
||||||
Vector3 operator+(const Vector3 &v) const;
|
Vector3 operator+(const Vector3& v) const;
|
||||||
Vector3 operator+=(const Vector3 &v);
|
Vector3 operator+=(const Vector3& v);
|
||||||
|
|
||||||
/// @brief Scale the vector using another vector
|
/// @brief Scale the vector using another vector
|
||||||
/// @param v1 The vector to scale
|
/// @param v1 The vector to scale
|
||||||
@ -140,16 +140,16 @@ public:
|
|||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each component of the vector v1 will be multiplied with the
|
/// @remark Each component of the vector v1 will be multiplied with the
|
||||||
/// matching component from the scaling vector v2.
|
/// matching component from the scaling vector v2.
|
||||||
static Vector3 Scale(const Vector3 &v1, const Vector3 &v2);
|
static Vector3 Scale(const Vector3& v1, const Vector3& v2);
|
||||||
/// @brief Scale the vector uniformly up
|
/// @brief Scale the vector uniformly up
|
||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each component of the vector will be multipled with the same
|
/// @remark Each component of the vector will be multipled with the same
|
||||||
/// factor f.
|
/// factor f.
|
||||||
friend Vector3 operator*(const Vector3 &v, float f) {
|
friend Vector3 operator*(const Vector3& v, float f) {
|
||||||
return Vector3(v.x * f, v.y * f, v.z * f);
|
return Vector3(v.x * f, v.y * f, v.z * f);
|
||||||
}
|
}
|
||||||
friend Vector3 operator*(float f, const Vector3 &v) {
|
friend Vector3 operator*(float f, const Vector3& v) {
|
||||||
// return Vector3(f * v.x, f * v.y, f * v.z);
|
// return Vector3(f * v.x, f * v.y, f * v.z);
|
||||||
return Vector3(v.x * f, v.y * f, v.z * f);
|
return Vector3(v.x * f, v.y * f, v.z * f);
|
||||||
}
|
}
|
||||||
@ -158,10 +158,10 @@ public:
|
|||||||
/// @param f The scaling factor
|
/// @param f The scaling factor
|
||||||
/// @return The scaled vector
|
/// @return The scaled vector
|
||||||
/// @remark Each componet of the vector will be divided by the same factor.
|
/// @remark Each componet of the vector will be divided by the same factor.
|
||||||
friend Vector3 operator/(const Vector3 &v, float f) {
|
friend Vector3 operator/(const Vector3& v, float f) {
|
||||||
return Vector3(v.x / f, v.y / f, v.z / f);
|
return Vector3(v.x / f, v.y / f, v.z / f);
|
||||||
}
|
}
|
||||||
friend Vector3 operator/(float f, const Vector3 &v) {
|
friend Vector3 operator/(float f, const Vector3& v) {
|
||||||
// return Vector3(f / v.x, f / v.y, f / v.z);
|
// return Vector3(f / v.x, f / v.y, f / v.z);
|
||||||
return Vector3(v.x / f, v.y / f, v.z / f);
|
return Vector3(v.x / f, v.y / f, v.z / f);
|
||||||
}
|
}
|
||||||
@ -171,31 +171,31 @@ public:
|
|||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The distance between the two vectors
|
/// @return The distance between the two vectors
|
||||||
static float Distance(const Vector3 &v1, const Vector3 &v2);
|
static float Distance(const Vector3& v1, const Vector3& v2);
|
||||||
|
|
||||||
/// @brief The dot product of two vectors
|
/// @brief The dot product of two vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The dot product of the two vectors
|
/// @return The dot product of the two vectors
|
||||||
static float Dot(const Vector3 &v1, const Vector3 &v2);
|
static float Dot(const Vector3& v1, const Vector3& v2);
|
||||||
|
|
||||||
/// @brief The cross product of two vectors
|
/// @brief The cross product of two vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
/// @param v2 The second vector
|
/// @param v2 The second vector
|
||||||
/// @return The cross product of the two vectors
|
/// @return The cross product of the two vectors
|
||||||
static Vector3 Cross(const Vector3 &v1, const Vector3 &v2);
|
static Vector3 Cross(const Vector3& v1, const Vector3& v2);
|
||||||
|
|
||||||
/// @brief Project the vector on another vector
|
/// @brief Project the vector on another vector
|
||||||
/// @param v The vector to project
|
/// @param v The vector to project
|
||||||
/// @param n The normal vecto to project on
|
/// @param n The normal vecto to project on
|
||||||
/// @return The projected vector
|
/// @return The projected vector
|
||||||
static Vector3 Project(const Vector3 &v, const Vector3 &n);
|
static Vector3 Project(const Vector3& v, const Vector3& n);
|
||||||
/// @brief Project the vector on a plane defined by a normal orthogonal to the
|
/// @brief Project the vector on a plane defined by a normal orthogonal to the
|
||||||
/// plane.
|
/// plane.
|
||||||
/// @param v The vector to project
|
/// @param v The vector to project
|
||||||
/// @param n The normal of the plane to project on
|
/// @param n The normal of the plane to project on
|
||||||
/// @return Teh projected vector
|
/// @return Teh projected vector
|
||||||
static Vector3 ProjectOnPlane(const Vector3 &v, const Vector3 &n);
|
static Vector3 ProjectOnPlane(const Vector3& v, const Vector3& n);
|
||||||
|
|
||||||
/// @brief The angle between two vectors
|
/// @brief The angle between two vectors
|
||||||
/// @param v1 The first vector
|
/// @param v1 The first vector
|
||||||
@ -204,14 +204,15 @@ public:
|
|||||||
/// @remark This reterns an unsigned angle which is the shortest distance
|
/// @remark This reterns an unsigned angle which is the shortest distance
|
||||||
/// between the two vectors. Use Vector3::SignedAngle if a signed angle is
|
/// between the two vectors. Use Vector3::SignedAngle if a signed angle is
|
||||||
/// needed.
|
/// needed.
|
||||||
static AngleOf<float> Angle(const Vector3 &v1, const Vector3 &v2);
|
static AngleOf<float> Angle(const Vector3& v1, const Vector3& v2);
|
||||||
/// @brief The signed angle between two vectors
|
/// @brief The signed angle between two vectors
|
||||||
/// @param v1 The starting vector
|
/// @param v1 The starting vector
|
||||||
/// @param v2 The ending vector
|
/// @param v2 The ending vector
|
||||||
/// @param axis The axis to rotate around
|
/// @param axis The axis to rotate around
|
||||||
/// @return The signed angle between the two vectors
|
/// @return The signed angle between the two vectors
|
||||||
static AngleOf<float> SignedAngle(const Vector3 &v1, const Vector3 &v2,
|
static AngleOf<float> SignedAngle(const Vector3& v1,
|
||||||
const Vector3 &axis);
|
const Vector3& v2,
|
||||||
|
const Vector3& axis);
|
||||||
|
|
||||||
/// @brief Lerp (linear interpolation) between two vectors
|
/// @brief Lerp (linear interpolation) between two vectors
|
||||||
/// @param v1 The starting vector
|
/// @param v1 The starting vector
|
||||||
@ -221,12 +222,11 @@ public:
|
|||||||
/// @remark The factor f is unclamped. Value 0 matches the vector *v1*, Value
|
/// @remark The factor f is unclamped. Value 0 matches the vector *v1*, Value
|
||||||
/// 1 matches vector *v2*. Value -1 is vector *v1* minus the difference
|
/// 1 matches vector *v2*. Value -1 is vector *v1* minus the difference
|
||||||
/// between *v1* and *v2* etc.
|
/// between *v1* and *v2* etc.
|
||||||
static Vector3 Lerp(const Vector3 &v1, const Vector3 &v2, float f);
|
static Vector3 Lerp(const Vector3& v1, const Vector3& v2, float f);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace LinearAlgebra
|
} // namespace LinearAlgebra
|
||||||
} // namespace Passer
|
using namespace LinearAlgebra;
|
||||||
using namespace Passer::LinearAlgebra;
|
|
||||||
|
|
||||||
#include "Spherical.h"
|
#include "Spherical.h"
|
||||||
|
|
||||||
|
@ -1,11 +1,13 @@
|
|||||||
#if GTEST
|
#if GTEST
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
#include <limits>
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <limits>
|
||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
|
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
||||||
|
|
||||||
TEST(Angle16, Construct) {
|
TEST(Angle16, Construct) {
|
||||||
@ -86,7 +88,7 @@ TEST(Angle16, Normalize) {
|
|||||||
r = Angle16::Normalize(Angle16::Degrees(0));
|
r = Angle16::Normalize(Angle16::Degrees(0));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Normalize 0";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Normalize 0";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// Infinites are not supported
|
// Infinites are not supported
|
||||||
r = Angle16::Normalize(Angle16::Degrees(FLOAT_INFINITY));
|
r = Angle16::Normalize(Angle16::Degrees(FLOAT_INFINITY));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), FLOAT_INFINITY) << "Normalize INFINITY";
|
EXPECT_FLOAT_EQ(r.InDegrees(), FLOAT_INFINITY) << "Normalize INFINITY";
|
||||||
@ -125,7 +127,7 @@ TEST(Angle16, Clamp) {
|
|||||||
Angle16::Degrees(-10));
|
Angle16::Degrees(-10));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Clamp 0 10 -10";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Clamp 0 10 -10";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// Infinites are not supported
|
// Infinites are not supported
|
||||||
r = Angle16::Clamp(Angle16::Degrees(10), Angle16::Degrees(0),
|
r = Angle16::Clamp(Angle16::Degrees(10), Angle16::Degrees(0),
|
||||||
Angle16::Degrees(FLOAT_INFINITY));
|
Angle16::Degrees(FLOAT_INFINITY));
|
||||||
@ -216,7 +218,7 @@ TEST(Angle16, MoveTowards) {
|
|||||||
r = Angle16::MoveTowards(Angle16::Degrees(0), Angle16::Degrees(0), 30);
|
r = Angle16::MoveTowards(Angle16::Degrees(0), Angle16::Degrees(0), 30);
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "MoveTowards 0 0 30";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "MoveTowards 0 0 30";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// infinites are not supported
|
// infinites are not supported
|
||||||
r = Angle16::MoveTowards(Angle16::Degrees(0), Angle16::Degrees(90),
|
r = Angle16::MoveTowards(Angle16::Degrees(0), Angle16::Degrees(90),
|
||||||
FLOAT_INFINITY);
|
FLOAT_INFINITY);
|
||||||
|
@ -1,11 +1,13 @@
|
|||||||
#if GTEST
|
#if GTEST
|
||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
#include <limits>
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <limits>
|
||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
|
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
||||||
|
|
||||||
TEST(Angle8, Construct) {
|
TEST(Angle8, Construct) {
|
||||||
@ -86,7 +88,7 @@ TEST(Angle8, Normalize) {
|
|||||||
r = Angle8::Normalize(Angle8::Degrees(0));
|
r = Angle8::Normalize(Angle8::Degrees(0));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Normalize 0";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Normalize 0";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// Infinites are not supported
|
// Infinites are not supported
|
||||||
r = Angle8::Normalize(Angle8::Degrees(FLOAT_INFINITY));
|
r = Angle8::Normalize(Angle8::Degrees(FLOAT_INFINITY));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), FLOAT_INFINITY) << "Normalize INFINITY";
|
EXPECT_FLOAT_EQ(r.InDegrees(), FLOAT_INFINITY) << "Normalize INFINITY";
|
||||||
@ -124,7 +126,7 @@ TEST(Angle8, Clamp) {
|
|||||||
Angle8::Degrees(-10));
|
Angle8::Degrees(-10));
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Clamp 0 10 -10";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "Clamp 0 10 -10";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// Infinites are not supported
|
// Infinites are not supported
|
||||||
r = Angle8::Clamp(Angle8::Degrees(10), Angle8::Degrees(0),
|
r = Angle8::Clamp(Angle8::Degrees(10), Angle8::Degrees(0),
|
||||||
Angle8::Degrees(FLOAT_INFINITY));
|
Angle8::Degrees(FLOAT_INFINITY));
|
||||||
@ -215,7 +217,7 @@ TEST(Angle8, MoveTowards) {
|
|||||||
r = Angle8::MoveTowards(Angle8::Degrees(0), Angle8::Degrees(0), 30);
|
r = Angle8::MoveTowards(Angle8::Degrees(0), Angle8::Degrees(0), 30);
|
||||||
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "MoveTowards 0 0 30";
|
EXPECT_FLOAT_EQ(r.InDegrees(), 0) << "MoveTowards 0 0 30";
|
||||||
|
|
||||||
if (false) { // std::numeric_limits<float>::is_iec559) {
|
if (false) { // std::numeric_limits<float>::is_iec559) {
|
||||||
// infinites are not supported
|
// infinites are not supported
|
||||||
r = Angle8::MoveTowards(Angle8::Degrees(0), Angle8::Degrees(90),
|
r = Angle8::MoveTowards(Angle8::Degrees(0), Angle8::Degrees(90),
|
||||||
FLOAT_INFINITY);
|
FLOAT_INFINITY);
|
||||||
|
@ -1,11 +1,13 @@
|
|||||||
#if GTEST
|
#if GTEST
|
||||||
#include <gtest/gtest.h>
|
#include <gtest/gtest.h>
|
||||||
|
|
||||||
#include <limits>
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <limits>
|
||||||
|
|
||||||
#include "Angle.h"
|
#include "Angle.h"
|
||||||
|
|
||||||
|
using namespace LinearAlgebra;
|
||||||
|
|
||||||
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
#define FLOAT_INFINITY std::numeric_limits<float>::infinity()
|
||||||
|
|
||||||
TEST(AngleSingle, Construct) {
|
TEST(AngleSingle, Construct) {
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
#include "LowLevelMessages.h"
|
#include "LowLevelMessages.h"
|
||||||
|
|
||||||
#include "LinearAlgebra/float16.h"
|
|
||||||
// #include <iostream>
|
// #include <iostream>
|
||||||
|
#include "LinearAlgebra/float16.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
@ -42,30 +42,30 @@ float LowLevelMessages::ReceiveFloat16(const char* buffer,
|
|||||||
return (float)f.toFloat();
|
return (float)f.toFloat();
|
||||||
}
|
}
|
||||||
|
|
||||||
void LowLevelMessages::SendSpherical16(char* buffer,
|
void LowLevelMessages::SendSpherical(char* buffer,
|
||||||
unsigned char* ix,
|
unsigned char* ix,
|
||||||
Spherical16 s) {
|
Spherical s) {
|
||||||
SendFloat16(buffer, ix, s.distance);
|
SendFloat16(buffer, ix, s.distance);
|
||||||
SendAngle8(buffer, ix, s.direction.horizontal.InDegrees());
|
SendAngle8(buffer, ix, s.direction.horizontal.InDegrees());
|
||||||
SendAngle8(buffer, ix, s.direction.vertical.InDegrees());
|
SendAngle8(buffer, ix, s.direction.vertical.InDegrees());
|
||||||
}
|
}
|
||||||
Spherical16 LowLevelMessages::ReceiveSpherical16(const char* buffer,
|
Spherical LowLevelMessages::ReceiveSpherical(const char* buffer,
|
||||||
unsigned char* startIndex) {
|
unsigned char* startIndex) {
|
||||||
float distance = ReceiveFloat16(buffer, startIndex);
|
float distance = ReceiveFloat16(buffer, startIndex);
|
||||||
|
|
||||||
Angle8 horizontal8 = ReceiveAngle8(buffer, startIndex);
|
Angle8 horizontal8 = ReceiveAngle8(buffer, startIndex);
|
||||||
Angle16 horizontal = Angle16::Binary(horizontal8.GetBinary() * 256);
|
Angle horizontal = Angle::Radians(horizontal8.InRadians());
|
||||||
|
|
||||||
Angle8 vertical8 = ReceiveAngle8(buffer, startIndex);
|
Angle8 vertical8 = ReceiveAngle8(buffer, startIndex);
|
||||||
Angle16 vertical = Angle16::Binary(vertical8.GetBinary() * 256);
|
Angle vertical = Angle::Radians(vertical8.InRadians());
|
||||||
|
|
||||||
Spherical16 s = Spherical16(distance, horizontal, vertical);
|
Spherical s = Spherical(distance, horizontal, vertical);
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
void LowLevelMessages::SendQuat32(char* buffer,
|
void LowLevelMessages::SendQuat32(char* buffer,
|
||||||
unsigned char* ix,
|
unsigned char* ix,
|
||||||
SwingTwist16 rotation) {
|
SwingTwist rotation) {
|
||||||
Quaternion q = rotation.ToQuaternion();
|
Quaternion q = rotation.ToQuaternion();
|
||||||
unsigned char qx = (char)(q.x * 127 + 128);
|
unsigned char qx = (char)(q.x * 127 + 128);
|
||||||
unsigned char qy = (char)(q.y * 127 + 128);
|
unsigned char qy = (char)(q.y * 127 + 128);
|
||||||
@ -85,14 +85,14 @@ void LowLevelMessages::SendQuat32(char* buffer,
|
|||||||
buffer[(*ix)++] = qw;
|
buffer[(*ix)++] = qw;
|
||||||
}
|
}
|
||||||
|
|
||||||
SwingTwist16 LowLevelMessages::ReceiveQuat32(const char* buffer,
|
SwingTwist LowLevelMessages::ReceiveQuat32(const char* buffer,
|
||||||
unsigned char* ix) {
|
unsigned char* ix) {
|
||||||
float qx = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
float qx = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
||||||
float qy = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
float qy = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
||||||
float qz = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
float qz = (buffer[(*ix)++] - 128.0F) / 127.0F;
|
||||||
float qw = buffer[(*ix)++] / 255.0F;
|
float qw = buffer[(*ix)++] / 255.0F;
|
||||||
Quaternion q = Quaternion(qx, qy, qz, qw);
|
Quaternion q = Quaternion(qx, qy, qz, qw);
|
||||||
SwingTwist16 s = SwingTwist16::FromQuaternion(q);
|
SwingTwist s = SwingTwist::FromQuaternion(q);
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -11,11 +11,12 @@ class LowLevelMessages {
|
|||||||
static void SendFloat16(char* buffer, unsigned char* ix, float value);
|
static void SendFloat16(char* buffer, unsigned char* ix, float value);
|
||||||
static float ReceiveFloat16(const char* buffer, unsigned char* startIndex);
|
static float ReceiveFloat16(const char* buffer, unsigned char* startIndex);
|
||||||
|
|
||||||
static void SendSpherical16(char* buffer, unsigned char* ix, Spherical16 s);
|
static void SendSpherical(char* buffer, unsigned char* ix, Spherical s);
|
||||||
static Spherical16 ReceiveSpherical16(const char* buffer, unsigned char* startIndex);
|
static Spherical ReceiveSpherical(const char* buffer,
|
||||||
|
unsigned char* startIndex);
|
||||||
|
|
||||||
static void SendQuat32(char* buffer, unsigned char* ix, SwingTwist16 q);
|
static void SendQuat32(char* buffer, unsigned char* ix, SwingTwist q);
|
||||||
static SwingTwist16 ReceiveQuat32(const char* buffer, unsigned char* ix);
|
static SwingTwist ReceiveQuat32(const char* buffer, unsigned char* ix);
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace RoboidControl
|
} // namespace RoboidControl
|
||||||
|
@ -3,22 +3,6 @@
|
|||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
// PoseMsg::PoseMsg(unsigned char networkId,
|
|
||||||
// unsigned char thingId,
|
|
||||||
// unsigned char poseType,
|
|
||||||
// Spherical16 position,
|
|
||||||
// SwingTwist16 orientation,
|
|
||||||
// Spherical16 linearVelocity,
|
|
||||||
// Spherical16 angularVelocity) {
|
|
||||||
// this->networkId = networkId;
|
|
||||||
// this->thingId = thingId;
|
|
||||||
|
|
||||||
// this->poseType = poseType;
|
|
||||||
// this->position = position;
|
|
||||||
// this->orientation = orientation;
|
|
||||||
// this->linearVelocity = linearVelocity;
|
|
||||||
// this->angularVelocity = angularVelocity;
|
|
||||||
// }
|
|
||||||
PoseMsg::PoseMsg(unsigned char networkId, Thing* thing, bool force) {
|
PoseMsg::PoseMsg(unsigned char networkId, Thing* thing, bool force) {
|
||||||
this->networkId = networkId;
|
this->networkId = networkId;
|
||||||
this->thingId = thing->id;
|
this->thingId = thing->id;
|
||||||
@ -29,7 +13,7 @@ PoseMsg::PoseMsg(unsigned char networkId, Thing* thing, bool force) {
|
|||||||
this->poseType |= Pose_Position;
|
this->poseType |= Pose_Position;
|
||||||
thing->positionUpdated = false;
|
thing->positionUpdated = false;
|
||||||
}
|
}
|
||||||
if (thing->orientationUpdated || force ) {
|
if (thing->orientationUpdated || force) {
|
||||||
this->orientation = thing->GetOrientation();
|
this->orientation = thing->GetOrientation();
|
||||||
this->poseType |= Pose_Orientation;
|
this->poseType |= Pose_Orientation;
|
||||||
thing->orientationUpdated = false;
|
thing->orientationUpdated = false;
|
||||||
@ -51,7 +35,7 @@ PoseMsg::PoseMsg(const char* buffer) {
|
|||||||
this->networkId = buffer[ix++];
|
this->networkId = buffer[ix++];
|
||||||
this->thingId = buffer[ix++];
|
this->thingId = buffer[ix++];
|
||||||
this->poseType = buffer[ix++];
|
this->poseType = buffer[ix++];
|
||||||
this->position = LowLevelMessages::ReceiveSpherical16(buffer, &ix);
|
this->position = LowLevelMessages::ReceiveSpherical(buffer, &ix);
|
||||||
this->orientation = LowLevelMessages::ReceiveQuat32(buffer, &ix);
|
this->orientation = LowLevelMessages::ReceiveQuat32(buffer, &ix);
|
||||||
// linearVelocity
|
// linearVelocity
|
||||||
// angularVelocity
|
// angularVelocity
|
||||||
@ -69,13 +53,13 @@ unsigned char PoseMsg::Serialize(char* buffer) {
|
|||||||
buffer[ix++] = this->thingId;
|
buffer[ix++] = this->thingId;
|
||||||
buffer[ix++] = this->poseType;
|
buffer[ix++] = this->poseType;
|
||||||
if ((this->poseType & Pose_Position) != 0)
|
if ((this->poseType & Pose_Position) != 0)
|
||||||
LowLevelMessages::SendSpherical16(buffer, &ix, this->position);
|
LowLevelMessages::SendSpherical(buffer, &ix, this->position);
|
||||||
if ((this->poseType & Pose_Orientation) != 0)
|
if ((this->poseType & Pose_Orientation) != 0)
|
||||||
LowLevelMessages::SendQuat32(buffer, &ix, this->orientation);
|
LowLevelMessages::SendQuat32(buffer, &ix, this->orientation);
|
||||||
if ((this->poseType & Pose_LinearVelocity) != 0)
|
if ((this->poseType & Pose_LinearVelocity) != 0)
|
||||||
LowLevelMessages::SendSpherical16(buffer, &ix, this->linearVelocity);
|
LowLevelMessages::SendSpherical(buffer, &ix, this->linearVelocity);
|
||||||
if ((this->poseType & Pose_AngularVelocity) != 0)
|
if ((this->poseType & Pose_AngularVelocity) != 0)
|
||||||
LowLevelMessages::SendSpherical16(buffer, &ix, this->angularVelocity);
|
LowLevelMessages::SendSpherical(buffer, &ix, this->angularVelocity);
|
||||||
return ix;
|
return ix;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3,8 +3,8 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
/// @brief Message to communicate the pose of the thing
|
/// @brief Message to communicate the pose of the thing
|
||||||
/// The pose is in local space relative to the parent. If there is not parent (the thing is a root thing), the pose will
|
/// The pose is in local space relative to the parent. If there is not parent
|
||||||
/// be in world space.
|
/// (the thing is a root thing), the pose will be in world space.
|
||||||
class PoseMsg : public IMessage {
|
class PoseMsg : public IMessage {
|
||||||
public:
|
public:
|
||||||
/// @brief The message ID
|
/// @brief The message ID
|
||||||
@ -29,29 +29,14 @@ class PoseMsg : public IMessage {
|
|||||||
static const unsigned char Pose_AngularVelocity = 0x08;
|
static const unsigned char Pose_AngularVelocity = 0x08;
|
||||||
|
|
||||||
/// @brief The position of the thing in local space in meters
|
/// @brief The position of the thing in local space in meters
|
||||||
Spherical16 position;
|
Spherical position;
|
||||||
/// @brief The orientation of the thing in local space
|
/// @brief The orientation of the thing in local space
|
||||||
SwingTwist16 orientation;
|
SwingTwist orientation;
|
||||||
/// @brief The linear velocity of the thing in local space in meters per second
|
/// @brief The linear velocity of the thing in local space in meters per
|
||||||
Spherical16 linearVelocity;
|
/// second
|
||||||
|
Spherical linearVelocity;
|
||||||
/// @brief The angular velocity of the thing in local space
|
/// @brief The angular velocity of the thing in local space
|
||||||
Spherical16 angularVelocity;
|
Spherical angularVelocity;
|
||||||
|
|
||||||
/// @brief Create a new message for sending
|
|
||||||
/// @param networkId The network ID of the thing
|
|
||||||
/// @param thingId The ID of the thing
|
|
||||||
/// @param poseType Bit pattern stating which pose components are available
|
|
||||||
/// @param position The position of the thing in local space in meters
|
|
||||||
/// @param orientation The orientation of the thing in local space
|
|
||||||
/// @param linearVelocity The linear velocity of the thing in local space in meters per second
|
|
||||||
/// @param angularVelocity The angular velocity of the thing in local space
|
|
||||||
// PoseMsg(unsigned char networkId,
|
|
||||||
// unsigned char thingId,
|
|
||||||
// unsigned char poseType,
|
|
||||||
// Spherical16 position,
|
|
||||||
// SwingTwist16 orientation,
|
|
||||||
// Spherical16 linearVelocity = Spherical16(),
|
|
||||||
// Spherical16 angularVelocity = Spherical16());
|
|
||||||
|
|
||||||
/// @brief Create a new message for sending
|
/// @brief Create a new message for sending
|
||||||
/// @param networkId he network ID of the thing
|
/// @param networkId he network ID of the thing
|
||||||
|
@ -8,7 +8,7 @@ Participant::Participant() {}
|
|||||||
|
|
||||||
Participant::Participant(const char* ipAddress, int port) {
|
Participant::Participant(const char* ipAddress, int port) {
|
||||||
// make a copy of the ip address string
|
// make a copy of the ip address string
|
||||||
int addressLength = strlen(ipAddress);
|
int addressLength = (int)strlen(ipAddress);
|
||||||
int stringLength = addressLength + 1;
|
int stringLength = addressLength + 1;
|
||||||
char* addressString = new char[stringLength];
|
char* addressString = new char[stringLength];
|
||||||
#if defined(_WIN32) || defined(_WIN64)
|
#if defined(_WIN32) || defined(_WIN64)
|
||||||
|
46
Thing.cpp
46
Thing.cpp
@ -31,11 +31,11 @@ Thing::Thing(Participant* owner, int thingType) {
|
|||||||
this->type = thingType;
|
this->type = thingType;
|
||||||
this->networkId = 0;
|
this->networkId = 0;
|
||||||
|
|
||||||
this->position = Spherical16::zero;
|
this->position = Spherical::zero;
|
||||||
this->orientation = SwingTwist16::identity;
|
this->orientation = SwingTwist::identity;
|
||||||
|
|
||||||
this->linearVelocity = Spherical16::zero;
|
this->linearVelocity = Spherical::zero;
|
||||||
this->angularVelocity = Spherical16::zero;
|
this->angularVelocity = Spherical::zero;
|
||||||
|
|
||||||
// std::cout << "add thing to participant\n";
|
// std::cout << "add thing to participant\n";
|
||||||
owner->Add(this);
|
owner->Add(this);
|
||||||
@ -51,8 +51,8 @@ Thing::Thing(Participant* owner,
|
|||||||
this->id = thingId;
|
this->id = thingId;
|
||||||
this->type = (unsigned char)thingType;
|
this->type = (unsigned char)thingType;
|
||||||
|
|
||||||
this->linearVelocity = Spherical16::zero;
|
this->linearVelocity = Spherical::zero;
|
||||||
this->angularVelocity = Spherical16::zero;
|
this->angularVelocity = Spherical::zero;
|
||||||
// std::cout << "Created thing " << (int)this->networkId << "/" <<
|
// std::cout << "Created thing " << (int)this->networkId << "/" <<
|
||||||
// (int)this->id
|
// (int)this->id
|
||||||
// << "\n";
|
// << "\n";
|
||||||
@ -183,16 +183,20 @@ unsigned long Thing::GetTimeMs() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::Update() {
|
void Thing::Update(bool recursive) {
|
||||||
Update(GetTimeMs());
|
Update(GetTimeMs(), recursive);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::Update(unsigned long currentTimeMs) {
|
void Thing::Update(unsigned long currentTimeMs, bool recursive) {
|
||||||
(void)currentTimeMs;
|
(void)currentTimeMs;
|
||||||
|
if (recursive) {
|
||||||
// PoseMsg* poseMsg = new PoseMsg(this->networkId, this);
|
for (unsigned char childIx = 0; childIx < this->childCount; childIx++) {
|
||||||
// participant->Send(remoteParticipant, poseMsg);
|
Thing* child = this->children[childIx];
|
||||||
// delete poseMsg;
|
if (child == nullptr)
|
||||||
|
continue;
|
||||||
|
child->Update(currentTimeMs, recursive);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::UpdateThings(unsigned long currentTimeMs) {
|
void Thing::UpdateThings(unsigned long currentTimeMs) {
|
||||||
@ -207,38 +211,38 @@ void Thing::ProcessBinary(char* bytes) {
|
|||||||
(void)bytes;
|
(void)bytes;
|
||||||
};
|
};
|
||||||
|
|
||||||
void Thing::SetPosition(Spherical16 position) {
|
void Thing::SetPosition(Spherical position) {
|
||||||
this->position = position;
|
this->position = position;
|
||||||
this->positionUpdated = true;
|
this->positionUpdated = true;
|
||||||
}
|
}
|
||||||
Spherical16 Thing::GetPosition() {
|
Spherical Thing::GetPosition() {
|
||||||
return this->position;
|
return this->position;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::SetOrientation(SwingTwist16 orientation) {
|
void Thing::SetOrientation(SwingTwist orientation) {
|
||||||
this->orientation = orientation;
|
this->orientation = orientation;
|
||||||
this->orientationUpdated = true;
|
this->orientationUpdated = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
SwingTwist16 Thing::GetOrientation() {
|
SwingTwist Thing::GetOrientation() {
|
||||||
return this->orientation;
|
return this->orientation;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::SetLinearVelocity(Spherical16 linearVelocity) {
|
void Thing::SetLinearVelocity(Spherical linearVelocity) {
|
||||||
this->linearVelocity = linearVelocity;
|
this->linearVelocity = linearVelocity;
|
||||||
this->linearVelocityUpdated = true;
|
this->linearVelocityUpdated = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
Spherical16 Thing::GetLinearVelocity() {
|
Spherical Thing::GetLinearVelocity() {
|
||||||
return this->linearVelocity;
|
return this->linearVelocity;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Thing::SetAngularVelocity(Spherical16 angularVelocity) {
|
void Thing::SetAngularVelocity(Spherical angularVelocity) {
|
||||||
this->angularVelocity = angularVelocity;
|
this->angularVelocity = angularVelocity;
|
||||||
this->angularVelocityUpdated = true;
|
this->angularVelocityUpdated = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
Spherical16 Thing::GetAngularVelocity() {
|
Spherical Thing::GetAngularVelocity() {
|
||||||
return this->angularVelocity;
|
return this->angularVelocity;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
29
Thing.h
29
Thing.h
@ -119,16 +119,16 @@ class Thing {
|
|||||||
|
|
||||||
/// @brief Set the position of the thing
|
/// @brief Set the position of the thing
|
||||||
/// @param position The new position in local space, in meters
|
/// @param position The new position in local space, in meters
|
||||||
void SetPosition(Spherical16 position);
|
void SetPosition(Spherical position);
|
||||||
/// @brief Get the position of the thing
|
/// @brief Get the position of the thing
|
||||||
/// @return The position in local space, in meters
|
/// @return The position in local space, in meters
|
||||||
Spherical16 GetPosition();
|
Spherical GetPosition();
|
||||||
/// @brief Set the orientation of the thing
|
/// @brief Set the orientation of the thing
|
||||||
/// @param orientation The new orientation in local space
|
/// @param orientation The new orientation in local space
|
||||||
void SetOrientation(SwingTwist16 orientation);
|
void SetOrientation(SwingTwist orientation);
|
||||||
/// @brief Get the orientation of the thing
|
/// @brief Get the orientation of the thing
|
||||||
/// @return The orienation in local space
|
/// @return The orienation in local space
|
||||||
SwingTwist16 GetOrientation();
|
SwingTwist GetOrientation();
|
||||||
/// @brief The scale of the thing (deprecated I think)
|
/// @brief The scale of the thing (deprecated I think)
|
||||||
// float scale = 1; // assuming uniform scale
|
// float scale = 1; // assuming uniform scale
|
||||||
|
|
||||||
@ -140,16 +140,16 @@ class Thing {
|
|||||||
/// @brief Set the linear velocity of the thing
|
/// @brief Set the linear velocity of the thing
|
||||||
/// @param linearVelocity The new linear velocity in local space, in meters
|
/// @param linearVelocity The new linear velocity in local space, in meters
|
||||||
/// per second
|
/// per second
|
||||||
void SetLinearVelocity(Spherical16 linearVelocity);
|
void SetLinearVelocity(Spherical linearVelocity);
|
||||||
/// @brief Get the linear velocity of the thing
|
/// @brief Get the linear velocity of the thing
|
||||||
/// @return The linear velocity in local space, in meters per second
|
/// @return The linear velocity in local space, in meters per second
|
||||||
virtual Spherical16 GetLinearVelocity();
|
virtual Spherical GetLinearVelocity();
|
||||||
/// @brief Set the angular velocity of the thing
|
/// @brief Set the angular velocity of the thing
|
||||||
/// @param angularVelocity the new angular velocity in local space
|
/// @param angularVelocity the new angular velocity in local space
|
||||||
virtual void SetAngularVelocity(Spherical16 angularVelocity);
|
virtual void SetAngularVelocity(Spherical angularVelocity);
|
||||||
/// @brief Get the angular velocity of the thing
|
/// @brief Get the angular velocity of the thing
|
||||||
/// @return The angular velocity in local space
|
/// @return The angular velocity in local space
|
||||||
virtual Spherical16 GetAngularVelocity();
|
virtual Spherical GetAngularVelocity();
|
||||||
bool linearVelocityUpdated = false;
|
bool linearVelocityUpdated = false;
|
||||||
bool angularVelocityUpdated = false;
|
bool angularVelocityUpdated = false;
|
||||||
|
|
||||||
@ -157,16 +157,16 @@ class Thing {
|
|||||||
/// @brief The position in local space
|
/// @brief The position in local space
|
||||||
/// @remark When this Thing has a parent, the position is relative to the
|
/// @remark When this Thing has a parent, the position is relative to the
|
||||||
/// parent's position and orientation
|
/// parent's position and orientation
|
||||||
Spherical16 position;
|
Spherical position;
|
||||||
/// @brief The orientation in local space
|
/// @brief The orientation in local space
|
||||||
/// @remark When this Thing has a parent, the orientation is relative to the
|
/// @remark When this Thing has a parent, the orientation is relative to the
|
||||||
/// parent's orientation
|
/// parent's orientation
|
||||||
SwingTwist16 orientation;
|
SwingTwist orientation;
|
||||||
|
|
||||||
/// @brief The linear velocity in local space
|
/// @brief The linear velocity in local space
|
||||||
Spherical16 linearVelocity;
|
Spherical linearVelocity;
|
||||||
/// @brief The angular velocity in local spze
|
/// @brief The angular velocity in local spze
|
||||||
Spherical16 angularVelocity;
|
Spherical angularVelocity;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// @brief Terminated things are no longer updated
|
/// @brief Terminated things are no longer updated
|
||||||
@ -181,12 +181,11 @@ class Thing {
|
|||||||
|
|
||||||
static unsigned long GetTimeMs();
|
static unsigned long GetTimeMs();
|
||||||
|
|
||||||
void Update();
|
void Update(bool recursive = false);
|
||||||
|
|
||||||
/// @brief Updates the state of the thing
|
/// @brief Updates the state of the thing
|
||||||
/// @param currentTimeMs The current clock time in milliseconds
|
/// @param currentTimeMs The current clock time in milliseconds
|
||||||
virtual void Update(
|
virtual void Update(unsigned long currentTimeMs, bool recursive = false);
|
||||||
unsigned long currentTimeMs); // { (void)currentTimeMs; };
|
|
||||||
|
|
||||||
static void UpdateThings(unsigned long currentTimeMs);
|
static void UpdateThings(unsigned long currentTimeMs);
|
||||||
|
|
||||||
|
@ -1,20 +1,18 @@
|
|||||||
#include "DifferentialDrive.h"
|
#include "DifferentialDrive.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
DifferentialDrive::DifferentialDrive() : Thing() {}
|
||||||
|
|
||||||
RoboidControl::DifferentialDrive::DifferentialDrive(Participant* participant)
|
RoboidControl::DifferentialDrive::DifferentialDrive(Participant* participant)
|
||||||
: Thing(participant) {
|
: Thing(participant) {}
|
||||||
this->leftWheel = new Thing(participant);
|
|
||||||
this->rightWheel = new Thing(participant);
|
|
||||||
}
|
|
||||||
|
|
||||||
void DifferentialDrive::SetDimensions(float wheelDiameter,
|
void DifferentialDrive::SetDriveDimensions(float wheelDiameter,
|
||||||
float wheelSeparation) {
|
float wheelSeparation) {
|
||||||
this->wheelRadius =
|
this->wheelRadius =
|
||||||
wheelDiameter > 0 ? wheelDiameter / 2 : -wheelDiameter / 2;
|
wheelDiameter > 0 ? wheelDiameter / 2 : -wheelDiameter / 2;
|
||||||
this->wheelSeparation =
|
this->wheelSeparation =
|
||||||
wheelSeparation > 0 ? wheelSeparation : -wheelSeparation;
|
wheelSeparation > 0 ? wheelSeparation : -wheelSeparation;
|
||||||
this->rpsToMs = wheelDiameter * Passer::LinearAlgebra::pi;
|
this->rpsToMs = wheelDiameter * LinearAlgebra::pi;
|
||||||
|
|
||||||
float distance = this->wheelSeparation / 2;
|
float distance = this->wheelSeparation / 2;
|
||||||
if (leftWheel != nullptr)
|
if (leftWheel != nullptr)
|
||||||
@ -35,7 +33,17 @@ void DifferentialDrive::SetMotors(Thing* leftWheel, Thing* rightWheel) {
|
|||||||
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
this->rightWheel->SetPosition(Spherical(distance, Direction::right));
|
||||||
}
|
}
|
||||||
|
|
||||||
void DifferentialDrive::Update(unsigned long currentMs) {
|
void DifferentialDrive::SetWheelVelocity(float speedLeft, float speedRight) {
|
||||||
|
if (this->leftWheel != nullptr)
|
||||||
|
this->leftWheel->SetAngularVelocity(Spherical(speedLeft, Direction::left));
|
||||||
|
if (this->rightWheel != nullptr)
|
||||||
|
this->rightWheel->SetAngularVelocity(
|
||||||
|
Spherical(speedRight, Direction::right));
|
||||||
|
}
|
||||||
|
|
||||||
|
void DifferentialDrive::Update(unsigned long currentMs, bool recursive) {
|
||||||
|
if (this->linearVelocityUpdated == false)
|
||||||
|
return;
|
||||||
// this assumes forward velocity only....
|
// this assumes forward velocity only....
|
||||||
float linearVelocity = this->GetLinearVelocity().distance;
|
float linearVelocity = this->GetLinearVelocity().distance;
|
||||||
|
|
||||||
@ -49,16 +57,12 @@ void DifferentialDrive::Update(unsigned long currentMs) {
|
|||||||
float speedLeft =
|
float speedLeft =
|
||||||
(linearVelocity + angularSpeed * this->wheelSeparation / 2) /
|
(linearVelocity + angularSpeed * this->wheelSeparation / 2) /
|
||||||
this->wheelRadius * Rad2Deg;
|
this->wheelRadius * Rad2Deg;
|
||||||
if (this->leftWheel != nullptr)
|
|
||||||
this->leftWheel->SetAngularVelocity(Spherical(speedLeft, Direction::left));
|
|
||||||
|
|
||||||
float speedRight =
|
float speedRight =
|
||||||
(linearVelocity - angularSpeed * this->wheelSeparation / 2) /
|
(linearVelocity - angularSpeed * this->wheelSeparation / 2) /
|
||||||
this->wheelRadius * Rad2Deg;
|
this->wheelRadius * Rad2Deg;
|
||||||
if (this->rightWheel != nullptr)
|
|
||||||
this->rightWheel->SetAngularVelocity(
|
|
||||||
Spherical(speedRight, Direction::right));
|
|
||||||
|
|
||||||
|
this->SetWheelVelocity(speedLeft, speedRight);
|
||||||
|
Thing::Update(currentMs, recursive);
|
||||||
// std::cout << "lin. speed " << linearVelocity << " ang. speed " <<
|
// std::cout << "lin. speed " << linearVelocity << " ang. speed " <<
|
||||||
// angularVelocity.distance << " left wheel "
|
// angularVelocity.distance << " left wheel "
|
||||||
// << speedLeft << " right wheel " << speedRight << "\n";
|
// << speedLeft << " right wheel " << speedRight << "\n";
|
||||||
|
@ -5,14 +5,39 @@
|
|||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
|
||||||
/// @brief A thing which can move itself using a differential drive system
|
/// @brief A thing which can move itself using a differential drive system
|
||||||
|
///
|
||||||
|
/// @sa @link https://en.wikipedia.org/wiki/Differential_wheeled_robot @endlink
|
||||||
class DifferentialDrive : public Thing {
|
class DifferentialDrive : public Thing {
|
||||||
public:
|
public:
|
||||||
|
/// @brief Create a differential drive without networking support
|
||||||
|
DifferentialDrive();
|
||||||
|
/// @brief Create a differential drive with networking support
|
||||||
|
/// @param participant The local participant
|
||||||
DifferentialDrive(Participant* participant);
|
DifferentialDrive(Participant* participant);
|
||||||
|
|
||||||
void SetDimensions(float wheelDiameter, float wheelSeparation);
|
/// @brief Configures the dimensions of the drive
|
||||||
|
/// @param wheelDiameter The diameter of the wheels in meters
|
||||||
|
/// @param wheelSeparation The distance between the wheels in meters
|
||||||
|
///
|
||||||
|
/// These values are used to compute the desired wheel speed from the set
|
||||||
|
/// linear and angular velocity.
|
||||||
|
/// @sa SetLinearVelocity SetAngularVelocity
|
||||||
|
void SetDriveDimensions(float wheelDiameter, float wheelSeparation);
|
||||||
|
/// @brief Congures the motors for the wheels
|
||||||
|
/// @param leftWheel The motor for the left wheel
|
||||||
|
/// @param rightWheel The motor for the right wheel
|
||||||
void SetMotors(Thing* leftWheel, Thing* rightWheel);
|
void SetMotors(Thing* leftWheel, Thing* rightWheel);
|
||||||
|
|
||||||
virtual void Update(unsigned long currentMs) override;
|
/// @brief Directly specify the speeds of the motors
|
||||||
|
/// @param speedLeft The speed of the left wheel in degrees per second.
|
||||||
|
/// Positive moves the robot in the forward direction.
|
||||||
|
/// @param speedRight The speed of the right wheel in degrees per second.
|
||||||
|
/// Positive moves the robot in the forward direction.
|
||||||
|
|
||||||
|
void SetWheelVelocity(float speedLeft, float speedRight);
|
||||||
|
|
||||||
|
/// @copydoc RoboidControl::Thing::Update(unsigned long)
|
||||||
|
virtual void Update(unsigned long currentMs, bool recursive = true) override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/// @brief The radius of a wheel in meters
|
/// @brief The radius of a wheel in meters
|
||||||
@ -23,7 +48,9 @@ class DifferentialDrive : public Thing {
|
|||||||
/// @brief Convert revolutions per second to meters per second
|
/// @brief Convert revolutions per second to meters per second
|
||||||
float rpsToMs = 1.0f;
|
float rpsToMs = 1.0f;
|
||||||
|
|
||||||
|
/// @brief The left wheel
|
||||||
Thing* leftWheel = nullptr;
|
Thing* leftWheel = nullptr;
|
||||||
|
/// @brief The right wheel
|
||||||
Thing* rightWheel = nullptr;
|
Thing* rightWheel = nullptr;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1,10 +1,13 @@
|
|||||||
#include "TouchSensor.h"
|
#include "TouchSensor.h"
|
||||||
|
|
||||||
namespace RoboidControl {
|
namespace RoboidControl {
|
||||||
|
TouchSensor::TouchSensor() : Thing(Thing::Type::TouchSensor) {}
|
||||||
|
|
||||||
TouchSensor::TouchSensor(Participant* participant) : Thing(participant) {
|
TouchSensor::TouchSensor(Participant* participant)
|
||||||
this->touchedSomething = false;
|
: Thing(participant, Thing::Type::TouchSensor) {}
|
||||||
this->type = (unsigned char)Thing::Type::TouchSensor;
|
|
||||||
|
TouchSensor::TouchSensor(Thing* parent) : Thing(parent->owner) {
|
||||||
|
this->SetParent(parent);
|
||||||
}
|
}
|
||||||
|
|
||||||
void TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {}
|
void TouchSensor::GenerateBinary(char* bytes, unsigned char* ix) {}
|
||||||
|
@ -7,15 +7,20 @@ namespace RoboidControl {
|
|||||||
/// @brief A sensor which can detect touches
|
/// @brief A sensor which can detect touches
|
||||||
class TouchSensor : public Thing {
|
class TouchSensor : public Thing {
|
||||||
public:
|
public:
|
||||||
/// @brief Value which is true when the sensor is touching something, false otherwise
|
/// @brief Create a touch sensor with isolated participant
|
||||||
bool touchedSomething = false;
|
TouchSensor();
|
||||||
|
|
||||||
/// @brief Create a touch sensor
|
/// @brief Create a touch sensor
|
||||||
TouchSensor(Participant* participant);
|
TouchSensor(Participant* participant);
|
||||||
/// @brief Create a temperature sensor with the given ID
|
/// @brief Create a temperature sensor with the given ID
|
||||||
/// @param networkId The network ID of the sensor
|
/// @param networkId The network ID of the sensor
|
||||||
/// @param thingId The ID of the thing
|
/// @param thingId The ID of the thing
|
||||||
// TouchSensor(RemoteParticipant* participant, unsigned char networkId, unsigned char thingId);
|
TouchSensor(Thing* parent);
|
||||||
|
// TouchSensor(RemoteParticipant* participant, unsigned char networkId,
|
||||||
|
// unsigned char thingId);
|
||||||
|
|
||||||
|
/// @brief Value which is true when the sensor is touching something, false
|
||||||
|
/// otherwise
|
||||||
|
bool touchedSomething = false;
|
||||||
|
|
||||||
/// @brief Function to create a binary message with the temperature
|
/// @brief Function to create a binary message with the temperature
|
||||||
/// @param buffer The byte array for thw binary data
|
/// @param buffer The byte array for thw binary data
|
||||||
|
Loading…
x
Reference in New Issue
Block a user