mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: Vector2f::projected made const
This commit is contained in:
parent
daf56c5ab1
commit
46702e6c49
@ -295,7 +295,7 @@ void Vector2<T>::project(const Vector2<T> &v)
|
|||||||
|
|
||||||
// returns this vector projected onto v
|
// returns this vector projected onto v
|
||||||
template <typename T>
|
template <typename T>
|
||||||
Vector2<T> Vector2<T>::projected(const Vector2<T> &v)
|
Vector2<T> Vector2<T>::projected(const Vector2<T> &v) const
|
||||||
{
|
{
|
||||||
return v * (*this * v)/(v*v);
|
return v * (*this * v)/(v*v);
|
||||||
}
|
}
|
||||||
|
@ -161,7 +161,7 @@ struct Vector2
|
|||||||
void project(const Vector2<T> &v);
|
void project(const Vector2<T> &v);
|
||||||
|
|
||||||
// returns this vector projected onto v
|
// returns this vector projected onto v
|
||||||
Vector2<T> projected(const Vector2<T> &v);
|
Vector2<T> projected(const Vector2<T> &v) const;
|
||||||
|
|
||||||
// adjust position by a given bearing (in degrees) and distance
|
// adjust position by a given bearing (in degrees) and distance
|
||||||
void offset_bearing(T bearing, T distance);
|
void offset_bearing(T bearing, T distance);
|
||||||
|
Loading…
Reference in New Issue
Block a user