APM:Libraries
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
Vector2< T > Struct Template Reference

#include <vector2.h>

Collaboration diagram for Vector2< T >:
[legend]

Public Member Functions

constexpr Vector2 ()
 
constexpr Vector2 (const T x0, const T y0)
 
void operator() (const T x0, const T y0)
 
bool operator== (const Vector2< T > &v) const
 
bool operator!= (const Vector2< T > &v) const
 
Vector2< T > operator- (void) const
 
Vector2< T > operator+ (const Vector2< T > &v) const
 
Vector2< T > operator- (const Vector2< T > &v) const
 
Vector2< T > operator* (const T num) const
 
Vector2< T > operator/ (const T num) const
 
Vector2< T > & operator+= (const Vector2< T > &v)
 
Vector2< T > & operator-= (const Vector2< T > &v)
 
Vector2< T > & operator*= (const T num)
 
Vector2< T > & operator/= (const T num)
 
operator* (const Vector2< T > &v) const
 
operator% (const Vector2< T > &v) const
 
float angle (const Vector2< T > &v2) const
 
bool is_nan (void) const
 
bool is_inf (void) const
 
bool is_zero (void) const
 
T & operator[] (uint8_t i)
 
const T & operator[] (uint8_t i) const
 
void zero ()
 
length_squared () const
 
float length (void) const
 
void normalize ()
 
Vector2< T > normalized () const
 
void reflect (const Vector2< T > &n)
 
void project (const Vector2< T > &v)
 
Vector2< T > projected (const Vector2< T > &v)
 

Static Public Member Functions

static Vector2< T > perpendicular (const Vector2< T > &pos_delta, const Vector2< T > &v1)
 
static Vector2< T > closest_point (const Vector2< T > &p, const Vector2< T > &v, const Vector2< T > &w)
 
static float closest_distance_between_radial_and_point (const Vector2< T > &w, const Vector2< T > &p)
 
static bool segment_intersection (const Vector2< T > &seg1_start, const Vector2< T > &seg1_end, const Vector2< T > &seg2_start, const Vector2< T > &seg2_end, Vector2< T > &intersection)
 
static bool circle_segment_intersection (const Vector2< T > &seg_start, const Vector2< T > &seg_end, const Vector2< T > &circle_center, float radius, Vector2< T > &intersection)
 

Public Attributes

x
 
y
 

Detailed Description

template<typename T>
struct Vector2< T >

Definition at line 35 of file vector2.h.

Constructor & Destructor Documentation

◆ Vector2() [1/2]

template<typename T>
constexpr Vector2< T >::Vector2 ( )
inline

Definition at line 40 of file vector2.h.

◆ Vector2() [2/2]

template<typename T>
constexpr Vector2< T >::Vector2 ( const T  x0,
const T  y0 
)
inline

Definition at line 45 of file vector2.h.

Member Function Documentation

◆ angle()

template<typename T>
float Vector2< T >::angle ( const Vector2< T > &  v2) const

Definition at line 127 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), Vector2< int32_t >::operator()(), and AP_Landing_Deepstall::verify_breakout().

Here is the caller graph for this function:

◆ circle_segment_intersection()

template<typename T>
bool Vector2< T >::circle_segment_intersection ( const Vector2< T > &  seg_start,
const Vector2< T > &  seg_end,
const Vector2< T > &  circle_center,
float  radius,
Vector2< T > &  intersection 
)
static

Definition at line 180 of file vector2.cpp.

Referenced by AC_Avoid::adjust_velocity_circle_fence(), Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::closest_distance_between_radial_and_point().

Here is the caller graph for this function:

◆ closest_distance_between_radial_and_point()

template<typename T>
static float Vector2< T >::closest_distance_between_radial_and_point ( const Vector2< T > &  w,
const Vector2< T > &  p 
)
inlinestatic

Definition at line 216 of file vector2.h.

Referenced by closest_approach_xy().

Here is the caller graph for this function:

◆ closest_point()

template<typename T>
static Vector2<T> Vector2< T >::closest_point ( const Vector2< T > &  p,
const Vector2< T > &  v,
const Vector2< T > &  w 
)
inlinestatic

Definition at line 191 of file vector2.h.

Referenced by AC_Avoid::adjust_velocity_polygon(), and Vector2< int32_t >::closest_distance_between_radial_and_point().

Here is the caller graph for this function:

◆ is_inf()

template<typename T >
bool Vector2< T >::is_inf ( void  ) const

Definition at line 72 of file vector2.cpp.

Referenced by AP_AHRS::calc_trig(), Vector2< int32_t >::circle_segment_intersection(), Vector2< int32_t >::operator()(), and AP_AHRS_DCM::yaw_error_compass().

Here is the caller graph for this function:

◆ is_nan()

template<typename T >
bool Vector2< T >::is_nan ( void  ) const

Definition at line 66 of file vector2.cpp.

Referenced by AP_AHRS::calc_trig(), Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ is_zero()

template<typename T>
bool Vector2< T >::is_zero ( void  ) const
inline

Definition at line 105 of file vector2.h.

Referenced by AC_Avoid::adjust_velocity_beacon_fence(), AC_Avoid::adjust_velocity_polygon_fence(), AC_Avoid::adjust_velocity_proximity(), AC_Loiter::calc_desired_velocity(), Compass::consistent(), and AP_Beacon::get_next_boundary_point().

Here is the caller graph for this function:

◆ length()

template<typename T >
float Vector2< T >::length ( void  ) const

◆ length_squared()

template<typename T>
T Vector2< T >::length_squared ( ) const
inline

Definition at line 131 of file vector2.h.

Referenced by Vector2< int32_t >::closest_point().

Here is the caller graph for this function:

◆ normalize()

template<typename T>
void Vector2< T >::normalize ( void  )
inline

Definition at line 140 of file vector2.h.

Referenced by AP_AHRS::calc_trig(), AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(), AP_Landing_Deepstall::update_steering(), AP_L1_Control::update_waypoint(), and AP_AHRS_DCM::yaw_error_compass().

Here is the caller graph for this function:

◆ normalized()

template<typename T>
Vector2<T> Vector2< T >::normalized ( ) const
inline

Definition at line 146 of file vector2.h.

Referenced by Compass::consistent(), and AP_L1_Control::update_loiter().

Here is the caller graph for this function:

◆ operator!=()

template<typename T>
bool Vector2< T >::operator!= ( const Vector2< T > &  v) const

Definition at line 121 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator%()

template<typename T>
T Vector2< T >::operator% ( const Vector2< T > &  v) const

Definition at line 39 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator()()

template<typename T>
void Vector2< T >::operator() ( const T  x0,
const T  y0 
)
inline

Definition at line 50 of file vector2.h.

◆ operator*() [1/2]

template<typename T>
Vector2< T > Vector2< T >::operator* ( const T  num) const

Definition at line 91 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator*() [2/2]

template<typename T>
T Vector2< T >::operator* ( const Vector2< T > &  v) const

Definition at line 32 of file vector2.cpp.

◆ operator*=()

template<typename T>
Vector2< T > & Vector2< T >::operator*= ( const T  num)

Definition at line 45 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator+()

template<typename T>
Vector2< T > Vector2< T >::operator+ ( const Vector2< T > &  v) const

Definition at line 103 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator+=()

template<typename T>
Vector2< T > & Vector2< T >::operator+= ( const Vector2< T > &  v)

Definition at line 78 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator-() [1/2]

template<typename T >
Vector2< T > Vector2< T >::operator- ( void  ) const

Definition at line 109 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator-() [2/2]

template<typename T>
Vector2< T > Vector2< T >::operator- ( const Vector2< T > &  v) const

Definition at line 97 of file vector2.cpp.

◆ operator-=()

template<typename T>
Vector2< T > & Vector2< T >::operator-= ( const Vector2< T > &  v)

Definition at line 59 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator/()

template<typename T>
Vector2< T > Vector2< T >::operator/ ( const T  num) const

Definition at line 85 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator/=()

template<typename T>
Vector2< T > & Vector2< T >::operator/= ( const T  num)

Definition at line 52 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator==()

template<typename T>
template bool Vector2< T >::operator== ( const Vector2< T > &  v) const

Definition at line 115 of file vector2.cpp.

Referenced by Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::operator()().

Here is the caller graph for this function:

◆ operator[]() [1/2]

template<typename T>
T& Vector2< T >::operator[] ( uint8_t  i)
inline

Definition at line 108 of file vector2.h.

◆ operator[]() [2/2]

template<typename T>
const T& Vector2< T >::operator[] ( uint8_t  i) const
inline

Definition at line 116 of file vector2.h.

◆ perpendicular()

template<typename T>
static Vector2<T> Vector2< T >::perpendicular ( const Vector2< T > &  pos_delta,
const Vector2< T > &  v1 
)
inlinestatic

Definition at line 173 of file vector2.h.

Referenced by AP_Avoidance::perpendicular_xy().

Here is the caller graph for this function:

◆ project()

template<typename T>
void Vector2< T >::project ( const Vector2< T > &  v)
inline

Definition at line 160 of file vector2.h.

Referenced by Vector2< int32_t >::reflect().

Here is the caller graph for this function:

◆ projected()

template<typename T>
Vector2<T> Vector2< T >::projected ( const Vector2< T > &  v)
inline

Definition at line 166 of file vector2.h.

◆ reflect()

template<typename T>
void Vector2< T >::reflect ( const Vector2< T > &  n)
inline

Definition at line 152 of file vector2.h.

◆ segment_intersection()

template<typename T>
bool Vector2< T >::segment_intersection ( const Vector2< T > &  seg1_start,
const Vector2< T > &  seg1_end,
const Vector2< T > &  seg2_start,
const Vector2< T > &  seg2_end,
Vector2< T > &  intersection 
)
static

Definition at line 147 of file vector2.cpp.

Referenced by AC_Avoid::adjust_velocity_polygon(), Vector2< int32_t >::circle_segment_intersection(), and Vector2< int32_t >::closest_distance_between_radial_and_point().

Here is the caller graph for this function:

◆ zero()

template<typename T>
void Vector2< T >::zero ( void  )
inline

Member Data Documentation

◆ x

template<typename T>
T Vector2< T >::x

Definition at line 37 of file vector2.h.

Referenced by OpticalFlow_backend::_applyYaw(), Linux::OpticalFlow_Onboard::_run_optflow(), GCS_MAVLINK::_set_mode_common(), AC_Avoid::adjust_roll_pitch(), AC_Avoid::adjust_speed(), AC_Avoid::adjust_velocity(), AC_Avoid::adjust_velocity_polygon(), AC_AttitudeControl::ang_vel_limit(), AP_GPS::calc_blended_state(), AC_Loiter::calc_desired_velocity(), AP_AHRS::calc_trig(), AC_PosControl::check_for_ekf_xy_reset(), Vector2< int32_t >::circle_segment_intersection(), NavEKF2_core::EstimateTerrainOffset(), NavEKF3_core::EstimateTerrainOffset(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), NavEKF2_core::FuseOptFlow(), NavEKF3_core::FuseOptFlow(), NavEKF2_core::FuseSideslip(), NavEKF3_core::FuseSideslip(), NavEKF3_core::FuseVelPosNED(), AC_Circle::get_closest_point_on_circle(), AC_PID_2D::get_d(), AP_Beacon::get_next_boundary_point(), AC_Loiter::get_pilot_desired_acceleration(), AP_AHRS_NavEKF::get_relative_position_NE_home(), AP_AHRS_NavEKF::get_relative_position_NED_origin(), AC_PrecLand::get_target_position_cm(), Location_Class::get_vector_from_origin_NEU(), AC_WPNav::get_vector_NEU(), AP_Avoidance::get_vector_perpendicular(), Location_Class::get_vector_xy_from_origin_NE(), SoaringController::get_wind_corrected_drift(), NavEKF2_core::getLLH(), NavEKF3_core::getLLH(), NavEKF2_core::getPosNE(), NavEKF3_core::getPosNE(), NavEKF2_core::getWind(), NavEKF3_core::getWind(), AC_Fence::handle_msg(), AP_Proximity_Backend::init_boundary(), AC_Loiter::init_target(), NavEKF2_core::InitialiseVariables(), NavEKF3_core::InitialiseVariables(), AC_AttitudeControl::input_shaping_rate_predictor(), AC_PolyFence_loader::load_point_from_eeprom(), location_path_proportion(), DataFlash_Class::Log_Write_POS(), Vector2< int32_t >::operator!=(), Vector2< int32_t >::operator%(), Vector2< int32_t >::operator*(), Vector2< int32_t >::operator+(), Vector2< int32_t >::operator+=(), Vector2< int32_t >::operator-(), Vector2< int32_t >::operator-=(), Vector2< int32_t >::operator==(), Vector2< int32_t >::operator[](), Polygon_outside(), Linux::OpticalFlow_Onboard::push_gyro(), Linux::OpticalFlow_Onboard::push_gyro_bias(), AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(), SITL::CRRCSim::recv_fdm(), NavEKF2_core::ResetPosition(), NavEKF3_core::ResetPosition(), NavEKF2_core::ResetVelocity(), NavEKF3_core::ResetVelocity(), AP_AHRS_View::rotate_body_to_earth2D(), AP_AHRS::rotate_body_to_earth2D(), AP_AHRS_View::rotate_earth_to_body2D(), AP_AHRS::rotate_earth_to_body2D(), AC_PrecLand::run_estimator(), AC_PrecLand::run_output_prediction(), AC_PosControl::run_xy_controller(), AC_PolyFence_loader::save_point_to_eeprom(), NavEKF2_core::SelectVelPosFusion(), NavEKF3_core::SelectVelPosFusion(), AC_PID_2D::set_input(), AC_PI_2D::set_input(), AC_PID_2D::set_input_filter_d(), AC_PID_2D::set_integrator(), AC_PI_2D::set_integrator(), AC_Loiter::set_pilot_desired_acceleration(), NavEKF2_core::setAidingMode(), NavEKF3_core::setAidingMode(), NavEKF2_core::setWindMagStateLearningMode(), NavEKF3_core::setWindMagStateLearningMode(), AP_OpticalFlow_PX4Flow::timer(), AP_OpticalFlow_Pixart::update(), AP_OpticalFlow_SITL::update(), AP_Beacon_SITL::update(), AP_OpticalFlow_Onboard::update(), AP_Beacon::update_boundary_points(), AP_L1_Control::update_loiter(), AP_L1_Control::update_waypoint(), AP_Landing_Deepstall::verify_land(), NavEKF2_core::writeOptFlowMeas(), NavEKF3_core::writeOptFlowMeas(), and AP_AHRS_DCM::yaw_error_compass().

◆ y

template<typename T>
T Vector2< T >::y

Definition at line 37 of file vector2.h.

Referenced by OpticalFlow_backend::_applyYaw(), Linux::OpticalFlow_Onboard::_run_optflow(), GCS_MAVLINK::_set_mode_common(), AC_Avoid::adjust_roll_pitch(), AC_Avoid::adjust_speed(), AC_Avoid::adjust_velocity(), AC_Avoid::adjust_velocity_polygon(), AC_AttitudeControl::ang_vel_limit(), AP_GPS::calc_blended_state(), AC_Loiter::calc_desired_velocity(), AP_AHRS::calc_trig(), AC_PosControl::check_for_ekf_xy_reset(), Vector2< int32_t >::circle_segment_intersection(), NavEKF2_core::EstimateTerrainOffset(), NavEKF3_core::EstimateTerrainOffset(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), NavEKF2_core::FuseOptFlow(), NavEKF3_core::FuseOptFlow(), NavEKF2_core::FuseSideslip(), NavEKF3_core::FuseSideslip(), NavEKF3_core::FuseVelPosNED(), AC_Circle::get_closest_point_on_circle(), AC_PID_2D::get_d(), AP_Beacon::get_next_boundary_point(), AC_Loiter::get_pilot_desired_acceleration(), AP_AHRS_NavEKF::get_relative_position_NE_home(), AP_AHRS_NavEKF::get_relative_position_NED_origin(), AC_PrecLand::get_target_position_cm(), Location_Class::get_vector_from_origin_NEU(), AC_WPNav::get_vector_NEU(), AP_Avoidance::get_vector_perpendicular(), Location_Class::get_vector_xy_from_origin_NE(), SoaringController::get_wind_corrected_drift(), NavEKF2_core::getLLH(), NavEKF3_core::getLLH(), NavEKF2_core::getPosNE(), NavEKF3_core::getPosNE(), NavEKF2_core::getWind(), NavEKF3_core::getWind(), AC_Fence::handle_msg(), AP_Proximity_Backend::init_boundary(), AC_Loiter::init_target(), NavEKF2_core::InitialiseVariables(), NavEKF3_core::InitialiseVariables(), AC_AttitudeControl::input_shaping_rate_predictor(), AC_PolyFence_loader::load_point_from_eeprom(), location_path_proportion(), DataFlash_Class::Log_Write_POS(), Vector2< int32_t >::operator!=(), Vector2< int32_t >::operator%(), Vector2< int32_t >::operator*(), Vector2< int32_t >::operator+(), Vector2< int32_t >::operator+=(), Vector2< int32_t >::operator-(), Vector2< int32_t >::operator-=(), Vector2< int32_t >::operator==(), Polygon_outside(), Linux::OpticalFlow_Onboard::push_gyro(), Linux::OpticalFlow_Onboard::push_gyro_bias(), AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(), SITL::CRRCSim::recv_fdm(), NavEKF2_core::ResetPosition(), NavEKF3_core::ResetPosition(), NavEKF2_core::ResetVelocity(), NavEKF3_core::ResetVelocity(), AP_AHRS_View::rotate_body_to_earth2D(), AP_AHRS::rotate_body_to_earth2D(), AP_AHRS_View::rotate_earth_to_body2D(), AP_AHRS::rotate_earth_to_body2D(), AC_PrecLand::run_estimator(), AC_PrecLand::run_output_prediction(), AC_PosControl::run_xy_controller(), AC_PolyFence_loader::save_point_to_eeprom(), NavEKF2_core::SelectVelPosFusion(), NavEKF3_core::SelectVelPosFusion(), AC_PID_2D::set_input(), AC_PI_2D::set_input(), AC_PID_2D::set_input_filter_d(), AC_PID_2D::set_integrator(), AC_PI_2D::set_integrator(), AC_Loiter::set_pilot_desired_acceleration(), NavEKF2_core::setAidingMode(), NavEKF3_core::setAidingMode(), NavEKF2_core::setWindMagStateLearningMode(), NavEKF3_core::setWindMagStateLearningMode(), AP_OpticalFlow_PX4Flow::timer(), AP_OpticalFlow_Pixart::update(), AP_OpticalFlow_SITL::update(), AP_Beacon_SITL::update(), AP_OpticalFlow_Onboard::update(), AP_Beacon::update_boundary_points(), AP_L1_Control::update_loiter(), AP_L1_Control::update_waypoint(), AP_Landing_Deepstall::verify_land(), NavEKF2_core::writeOptFlowMeas(), NavEKF3_core::writeOptFlowMeas(), and AP_AHRS_DCM::yaw_error_compass().


The documentation for this struct was generated from the following files: