mirror of https://github.com/ArduPilot/ardupilot
AP_Math: Vector2f::projected made const
This commit is contained in:
parent
a05860bd64
commit
5702c6a672
|
@ -295,7 +295,7 @@ void Vector2<T>::project(const Vector2<T> &v)
|
|||
|
||||
// returns this vector projected onto v
|
||||
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);
|
||||
}
|
||||
|
|
|
@ -161,7 +161,7 @@ struct Vector2
|
|||
void project(const Vector2<T> &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
|
||||
void offset_bearing(T bearing, T distance);
|
||||
|
|
Loading…
Reference in New Issue