APM:Libraries
Functions
AP_Math.h File Reference
#include <cmath>
#include <limits>
#include <stdint.h>
#include <type_traits>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include "definitions.h"
#include "edc.h"
#include "location.h"
#include "matrix3.h"
#include "polygon.h"
#include "quaternion.h"
#include "rotations.h"
#include "vector2.h"
#include "vector3.h"
#include "spline5.h"
Include dependency graph for AP_Math.h:

Go to the source code of this file.

Functions

 AP_PARAMDEFV (Vector3f, Vector3f, AP_PARAM_VECTOR3F)
 
template<typename Arithmetic1 , typename Arithmetic2 >
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal (const Arithmetic1 v_1, const Arithmetic2 v_2)
 
template<typename Arithmetic1 , typename Arithmetic2 >
std::enable_if< std::is_floating_point< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value, bool >::type is_equal (const Arithmetic1 v_1, const Arithmetic2 v_2)
 
template<typename T >
bool is_zero (const T fVal1)
 
template<typename T >
bool is_positive (const T fVal1)
 
template<typename T >
bool is_negative (const T fVal1)
 
template<typename T >
float safe_asin (const T v)
 
template<typename T >
float safe_sqrt (const T v)
 
bool inverse3x3 (float m[], float invOut[])
 
bool inverse4x4 (float m[], float invOut[])
 
float * mat_mul (float *A, float *B, uint8_t n)
 
bool inverse (float x[], float y[], uint16_t dim)
 
template<typename T >
float wrap_180 (const T angle, float unit_mod=1)
 
template<typename T >
auto wrap_180_cd (const T angle) -> decltype(wrap_180(angle, 100.f))
 
template<typename T >
float wrap_360 (const T angle, float unit_mod=1)
 
template<typename T >
auto wrap_360_cd (const T angle) -> decltype(wrap_360(angle, 100.f))
 
template<typename T >
float wrap_PI (const T radian)
 
template<typename T >
float wrap_2PI (const T radian)
 
template<typename T >
constrain_value (const T amt, const T low, const T high)
 
float constrain_float (const float amt, const float low, const float high)
 
int16_t constrain_int16 (const int16_t amt, const int16_t low, const int16_t high)
 
int32_t constrain_int32 (const int32_t amt, const int32_t low, const int32_t high)
 
static constexpr float radians (float deg)
 
static constexpr float degrees (float rad)
 
template<typename T >
float sq (const T val)
 
template<typename T , typename... Params>
float sq (const T first, const Params... parameters)
 
template<typename T , typename U , typename... Params>
float norm (const T first, const U second, const Params... parameters)
 
template<typename A , typename B >
static auto MIN (const A &one, const B &two) -> decltype(one< two ? one :two)
 
template<typename A , typename B >
static auto MAX (const A &one, const B &two) -> decltype(one > two ? one :two)
 
uint32_t hz_to_nsec (uint32_t freq)
 
uint32_t nsec_to_hz (uint32_t nsec)
 
uint32_t usec_to_nsec (uint32_t usec)
 
uint32_t nsec_to_usec (uint32_t nsec)
 
uint32_t hz_to_usec (uint32_t freq)
 
uint32_t usec_to_hz (uint32_t usec)
 
float linear_interpolate (float low_output, float high_output, float var_value, float var_low, float var_high)
 
uint16_t get_random16 (void)
 
float rand_float (void)
 
Vector3f rand_vec3f (void)
 
bool is_valid_octal (uint16_t octal)
 

Function Documentation

◆ AP_PARAMDEFV()

AP_PARAMDEFV ( Vector3f  ,
Vector3f  ,
AP_PARAM_VECTOR3F   
)

◆ constrain_float()

float constrain_float ( const float  amt,
const float  low,
const float  high 
)
inline

Definition at line 142 of file AP_Math.h.

Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), HALSITL::SITL_State::_output_to_flightgear(), AP_TECS::_update_pitch(), HALSITL::SITL_State::_update_rangefinder(), AP_InertialSensor_Backend::_update_sensor_rate(), AP_TECS::_update_speed_demand(), AP_TECS::_update_throttle_with_airspeed(), AP_TECS::_update_throttle_without_airspeed(), AP_Airspeed_MS4525::_voltage_correction(), AP_AHRS::add_trim(), AC_Avoid::adjust_roll_pitch(), AC_WPNav::advance_spline_target_along_track(), AC_WPNav::advance_wp_target_along_track(), AP_AHRS_DCM::airspeed_estimate(), AP_AHRS::airspeed_estimate(), AC_AttitudeControl::ang_vel_limit(), DigitalLPF< Vector2f >::apply(), AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(), AP_GPS::calc_blended_state(), AC_Loiter::calc_desired_velocity(), AP_Motors::calc_pwm_output_0to1(), AP_Motors::calc_pwm_output_1to1(), AP_MotorsHeli::calc_pwm_output_1to1_swash_servo(), AP_MotorsMulticopter::calc_spin_up_to_pwm(), AP_MotorsMulticopter::calc_thrust_to_pwm(), AP_AHRS::calc_trig(), AC_Circle::calc_velocities(), NavEKF2_core::calcFiltBaroOffset(), NavEKF3_core::calcFiltBaroOffset(), NavEKF2_core::calcGpsGoodForFlight(), NavEKF3_core::calcGpsGoodForFlight(), NavEKF2_core::calcGpsGoodToAlign(), NavEKF3_core::calcGpsGoodToAlign(), NavEKF2_core::calcOutputStates(), NavEKF3_core::calcOutputStates(), AP_MotorsHeli_RSC::calculate_desired_throttle(), SITL::Motor::calculate_forces(), Compass::calculate_heading(), DigitalLPF< Vector2f >::compute_alpha(), Compass::consistent(), NavEKF2_core::ConstrainStates(), NavEKF3_core::ConstrainStates(), NavEKF2_core::ConstrainVariances(), NavEKF3_core::ConstrainVariances(), NavEKF2_core::correctEkfOriginHeight(), NavEKF3_core::correctEkfOriginHeight(), NavEKF2_core::CovariancePrediction(), NavEKF3_core::CovariancePrediction(), AP_AHRS_DCM::drift_correction(), AC_AttitudeControl::euler_accel_limit(), SITL::FlightAxis::exchange_data(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), NavEKF2_core::FuseMagnetometer(), NavEKF3_core::FuseMagnetometer(), NavEKF2_core::FuseOptFlow(), NavEKF3_core::FuseOptFlow(), NavEKF2_core::FuseVelPosNED(), NavEKF3_core::FuseVelPosNED(), AP_MotorsMulticopter::get_compensation_gain(), AP_MotorsMulticopter::get_current_limit_max_throttle(), get_declination(), AR_AttitudeControl::get_desired_speed_accel_limited(), AC_InputManager_Heli::get_pilot_desired_collective(), AC_AttitudeControl_Heli::get_roll_trim_rad(), AP_YawController::get_servo_out(), AP_WheelEncoder::get_signal_quality(), AR_AttitudeControl::get_steering_out_heading(), AP_SteerController::get_steering_out_rate(), AR_AttitudeControl::get_steering_out_rate(), AC_PosControl::get_stopping_point_xy(), AC_PosControl::get_stopping_point_z(), AP_Motors::get_throttle(), AC_AttitudeControl_Sub::get_throttle_avg_max(), AC_AttitudeControl_Multi::get_throttle_avg_max(), AP_Motors::get_throttle_bidirectional(), AC_AttitudeControl_Sub::get_throttle_boosted(), AC_AttitudeControl_Multi::get_throttle_boosted(), AR_AttitudeControl::get_throttle_out_speed(), SITL::Plane::getTorque(), AP_GPS::init(), AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(), AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(), AC_AttitudeControl::input_shaping_ang_vel(), AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors(), AP_Landing_Deepstall::Log(), DataFlash_Class::Log_Write_POS(), AP_L1_Control::loiter_radius(), longitude_scale(), AP_MotorsHeli_Single::move_actuators(), SRV_Channels::move_servo(), AP_MotorsHeli_Single::move_yaw(), AP_L1_Control::nav_roll_cd(), RC_Channel::norm_input(), RC_Channel::norm_input_dz(), AP_MotorsHeli_RSC::output(), AP_MotorsTailsitter::output_armed_stabilizing(), AP_MotorsMatrix::output_armed_stabilizing(), AP_Motors6DOF::output_armed_stabilizing(), AP_MotorsCoax::output_armed_stabilizing(), AP_MotorsSingle::output_armed_stabilizing(), AP_MotorsTri::output_armed_stabilizing(), AP_Motors6DOF::output_armed_stabilizing_vectored(), AP_Motors6DOF::output_armed_stabilizing_vectored_6dof(), AP_MotorsMulticopter::output_boost_throttle(), AP_MotorsMulticopter::output_logic(), AP_MotorsTailsitter::output_to_motors(), AP_Landing_Deepstall::override_servos(), AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(), AP_Landing_Deepstall::predict_travel_distance(), SoloGimbalEKF::predictStates(), AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(), AC_AttitudeControl::rate_target_to_motor_pitch(), AC_AttitudeControl::rate_target_to_motor_roll(), AC_AttitudeControl_Heli::rate_target_to_motor_yaw(), AC_AttitudeControl::rate_target_to_motor_yaw(), NavEKF2_core::readGpsData(), NavEKF3_core::readGpsData(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), AP_Winch::release_length(), AP_RSSI::scale_and_constrain_float_rssi(), AP_SmartRTL::segment_segment_dist(), NavEKF2_core::selectHeightForFusion(), NavEKF3_core::selectHeightForFusion(), SITL::CRRCSim::send_servos_fixed_wing(), SITL::CRRCSim::send_servos_heli(), AC_PosControl_Sub::set_alt_target_from_climb_rate_ff(), AC_PosControl::set_alt_target_from_climb_rate_ff(), AC_PosControl::set_alt_target_with_slew(), AP_Winch::set_desired_rate(), AP_Param::set_float(), AC_AttitudeControl_Heli::set_hover_roll_trim_scalar(), ChibiOS::Util::set_imu_temp(), PX4::PX4Util::set_imu_temp(), VRBRAIN::VRBRAINUtil::set_imu_temp(), AC_AttitudeControl::set_input_tc(), AP_TECS::set_path_proportion(), AC_InputManager_Heli::set_stab_col_ramp(), AP_Motors::set_throttle_avg_max(), AP_MotorsHeli_RSC::set_throttle_curve(), AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(), AP_AHRS::set_trim(), AC_WPNav::set_wp_origin_and_destination(), NavEKF2_core::setAidingMode(), NavEKF2_core::setWindMagStateLearningMode(), NavEKF3_core::setWindMagStateLearningMode(), SITL::Aircraft::smooth_sensors(), AC_AttitudeControl::sqrt_controller(), AP_AutoTune::start(), TEST(), AC_AttitudeControl::thrust_heading_rotation_angles(), Airspeed_Calibration::update(), SITL::Gimbal::update(), AP_RPM_Pin::update(), AP_Winch_Servo::update(), AP_RPM_PX4_PWM::update(), SITL::Helicopter::update(), SITL::Gripper_Servo::update(), SITL::SingleCopter::update(), SITL::FlightAxis::update(), SITL::Sprayer::update(), SITL::ICEngine::update(), AC_AttitudeControl_Sub::update_althold_lean_angle_max(), AC_AttitudeControl_Multi::update_althold_lean_angle_max(), AC_AttitudeControl_Heli::update_althold_lean_angle_max(), AC_AttitudeControl::update_ang_vel_target_from_att_error(), AP_Airspeed::update_calibration(), SITL::Aircraft::update_dynamics(), AP_L1_Control::update_heading_hold(), AP_MotorsMulticopter::update_lift_max_from_batt_voltage(), AP_L1_Control::update_loiter(), AP_TECS::update_pitch_throttle(), SITL::Tracker::update_position_servos(), AP_BattMonitor_Backend::update_resistance_estimate(), SITL::Motor::update_servo(), AP_Landing_Deepstall::update_steering(), AP_Mount_Backend::update_targets_from_rc(), AP_MotorsMulticopter::update_throttle_hover(), AC_AttitudeControl_Sub::update_throttle_rpy_mix(), AC_AttitudeControl_Multi::update_throttle_rpy_mix(), AP_L1_Control::update_waypoint(), NavEKF2_core::writeOptFlowMeas(), and NavEKF3_core::writeOptFlowMeas().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constrain_int16()

int16_t constrain_int16 ( const int16_t  amt,
const int16_t  low,
const int16_t  high 
)
inline

◆ constrain_int32()

int32_t constrain_int32 ( const int32_t  amt,
const int32_t  low,
const int32_t  high 
)
inline

Definition at line 152 of file AP_Math.h.

Referenced by AP_Compass_BMM150::_compensate_z(), TEST(), AP_Landing::type_slope_constrain_roll(), and AP_Landing::type_slope_get_target_airspeed_cm().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constrain_value()

template<typename T >
T constrain_value ( const T  amt,
const T  low,
const T  high 
)

Definition at line 182 of file AP_Math.cpp.

Referenced by constrain_float(), constrain_int16(), constrain_int32(), is_negative(), and TEST().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ degrees()

static constexpr float degrees ( float  rad)
inlinestatic

Definition at line 164 of file AP_Math.h.

◆ get_random16()

uint16_t get_random16 ( void  )

Definition at line 212 of file AP_Math.cpp.

Referenced by rand_num(), FlashTest::setup(), CompassCalibrator::thin_samples(), and usec_to_hz().

Here is the caller graph for this function:

◆ hz_to_nsec()

uint32_t hz_to_nsec ( uint32_t  freq)
inline

Definition at line 207 of file AP_Math.h.

Referenced by Linux::PWM_Sysfs_Base::set_freq().

Here is the caller graph for this function:

◆ hz_to_usec()

uint32_t hz_to_usec ( uint32_t  freq)
inline

Definition at line 227 of file AP_Math.h.

Referenced by RCOutputRGBLed::hw_set_rgb(), and Linux::PeriodicThread::set_rate().

Here is the caller graph for this function:

◆ inverse()

bool inverse ( float  x[],
float  y[],
uint16_t  dim 
)

Definition at line 433 of file matrix_alg.cpp.

Referenced by Matrix3< float >::invert(), is_negative(), CompassCalibrator::run_ellipsoid_fit(), AccelCalibrator::run_fit(), CompassCalibrator::run_sphere_fit(), and test_matrix_inverse().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inverse3x3()

bool inverse3x3 ( float  m[],
float  invOut[] 
)

Definition at line 243 of file matrix_alg.cpp.

Referenced by inverse(), and is_negative().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inverse4x4()

bool inverse4x4 ( float  m[],
float  invOut[] 
)

Definition at line 282 of file matrix_alg.cpp.

Referenced by inverse(), and is_negative().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_equal() [1/2]

template<typename Arithmetic1 , typename Arithmetic2 >
std::enable_if<std::is_integral<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value ,bool>::type is_equal ( const Arithmetic1  v_1,
const Arithmetic2  v_2 
)

Definition at line 12 of file AP_Math.cpp.

◆ is_equal() [2/2]

template<typename Arithmetic1 , typename Arithmetic2 >
std::enable_if<std::is_floating_point<typename std::common_type<Arithmetic1, Arithmetic2>::type>::value, bool>::type is_equal ( const Arithmetic1  v_1,
const Arithmetic2  v_2 
)

◆ is_negative()

template<typename T >
bool is_negative ( const T  fVal1)
inline

Definition at line 61 of file AP_Math.h.

Referenced by AC_Avoid::adjust_speed(), AP_RangeFinder_NMEA::decode_latest_term(), AC_AttitudeControl::euler_accel_limit(), AR_AttitudeControl::get_steering_out_lat_accel(), AR_AttitudeControl::get_steering_out_rate(), AR_AttitudeControl::get_throttle_out_speed(), AP_Mission::mavlink_int_to_mission_cmd(), AC_AttitudeControl::rate_target_to_motor_pitch(), AC_AttitudeControl::rate_target_to_motor_roll(), AC_AttitudeControl::rate_target_to_motor_yaw(), AC_AttitudeControl::sqrt_controller(), AC_AttitudeControl::stopping_point(), and AP_Winch_Servo::update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_positive()

template<typename T >
bool is_positive ( const T  fVal1)
inline

◆ is_valid_octal()

bool is_valid_octal ( uint16_t  octal)

Definition at line 241 of file AP_Math.cpp.

Referenced by AP_ADSB::update(), and usec_to_hz().

Here is the caller graph for this function:

◆ is_zero()

template<typename T >
bool is_zero ( const T  fVal1)
inline

Definition at line 40 of file AP_Math.h.

Referenced by OpticalFlow_backend::_applyYaw(), AP_GPS_SBP2::_attempt_state_update(), AP_GeodesicGrid::_from_neighbor_umbrella(), AP_TECS::_get_i_gain(), AP_PitchController::_get_rate_out(), F4Light::Scheduler::_print_stats(), AP_GeodesicGrid::_subtriangle_index(), AP_GeodesicGrid::_triangle_index(), AP_Compass_LSM9DS1::_update(), AP_Compass_AK8963::_update(), HALSITL::SITL_State::_update_airspeed(), AP_TECS::_update_pitch(), HALSITL::SITL_State::_update_rangefinder(), AP_TECS::_update_throttle_with_airspeed(), AP_InertialSensor::accel_calibrated_ok_all(), AC_AttitudeControl::accel_limiting(), SRV_Channels::adjust_trim(), AC_Avoid::adjust_velocity_circle_fence(), AC_Avoid::adjust_velocity_polygon(), AC_WPNav::advance_spline_target_along_track(), AC_AttitudeControl::ang_vel_limit(), AC_AttitudeControl::ang_vel_to_euler_rate(), DigitalBiquadFilter< Vector3f >::apply(), NotchFilterVector3fParam::apply(), AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(), AP_Landing_Deepstall::build_approach_path(), AC_Loiter::calc_desired_velocity(), AC_PI_2D::calc_filt_alpha(), AC_PID_2D::calc_filt_alpha(), AC_PID_2D::calc_filt_alpha_d(), AP_AHRS::calc_trig(), SITL::Motor::calculate_forces(), AP_TempCalibration::calculate_p_range(), AC_WPNav::calculate_wp_leash_length(), AC_Fence::check_fence_alt_max(), AC_Fence::check_fence_circle(), Compass::configured(), AP_AHRS_DCM::drift_correction(), AC_AttitudeControl::euler_accel_limit(), SITL::FlightAxis::exchange_data(), AP_Compass_Backend::field_ok(), Quaternion::from_axis_angle(), Quaternion::from_axis_angle_fast(), AC_Loiter::get_angle_max_cd(), AC_Circle::get_closest_point_on_circle(), AP_MotorsMulticopter::get_current_limit_max_throttle(), AP_Baro::get_EAS2TAS(), AC_PID::get_filt_alpha(), AP_Baro::get_ground_temperature(), AC_PID_2D::get_i(), AC_PI_2D::get_i(), AC_PID::get_i(), AC_PID_2D::get_i_shrink(), AC_PI_2D::get_i_shrink(), AC_HELI_PID::get_leaky_i(), AC_PosControl::get_lean_angle_max_cd(), AP_Scheduler::get_loop_period_s(), AC_Avoid::get_max_speed(), AP_Beacon::get_origin(), AP_SteerController::get_steering_out_rate(), AR_AttitudeControl::get_stopping_distance(), AC_Avoid::get_stopping_distance(), AC_PosControl::get_stopping_point_xy(), AR_AttitudeControl::get_throttle_out_stop(), SITL::Plane::getForce(), SITL::Plane::getTorque(), Compass::handle_mag_cal_command(), AP_Baro::init(), Matrix3< float >::inverse(), inverse3x3(), inverse4x4(), AP_TempCalibration::learn_calibration(), location_offset(), AP_L1_Control::loiter_radius(), AP_MotorsMatrix::normalise_rpy_factors(), Quaternion::normalize(), AP_MotorsMatrix::output_armed_stabilizing(), AP_MotorsCoax::output_armed_stabilizing(), AP_MotorsTri::output_armed_stabilizing(), AP_MotorsSingle::output_armed_stabilizing(), AP_Motors6DOF::output_armed_stabilizing_vectored(), AP_MotorsMulticopter::output_logic(), AP_Baro_Backend::pressure_ok(), SITL::Aircraft::rand_normal(), AP_Winch::release_length(), AP_Landing_Deepstall::request_go_around(), Quaternion::rotate_fast(), AP_RSSI::scale_and_constrain_float_rssi(), AP_SmartRTL::segment_segment_dist(), AC_PosControl_Sub::set_alt_target_from_climb_rate_ff(), AC_PosControl::set_alt_target_from_climb_rate_ff(), AC_PosControl::set_alt_target_with_slew(), AC_WPNav::set_wp_origin_and_destination(), AC_PosControl::shift_alt_target(), SITL::Sprayer::should_report(), AC_AttitudeControl::sqrt_controller(), AC_PosControl::sqrt_controller(), AP_Mount_Servo::stabilize(), AC_AttitudeControl::stopping_point(), TEST(), AC_AttitudeControl::thrust_heading_rotation_angles(), Quaternion::to_axis_angle(), AP_Landing::type_slope_setup_landing_glide_slope(), AP_RPM_Pin::update(), AP_RPM_PX4_PWM::update(), AC_Circle::update(), AP_Camera::update(), AC_AttitudeControl_Sub::update_althold_lean_angle_max(), AC_AttitudeControl_Multi::update_althold_lean_angle_max(), AP_Baro_Backend::update_healthy_flag(), AP_BattMonitor_Backend::update_resistance_estimate(), AP_Avoidance::update_threat_level(), AP_Landing_Deepstall::verify_land(), and wgsecef2llh().

Here is the caller graph for this function:

◆ linear_interpolate()

float linear_interpolate ( float  low_output,
float  high_output,
float  var_value,
float  var_low,
float  var_high 
)

Definition at line 81 of file AP_Math.cpp.

Referenced by AP_Tuning::check_input(), AP_Landing_Deepstall::override_servos(), and usec_to_hz().

Here is the caller graph for this function:

◆ mat_mul()

float* mat_mul ( float *  A,
float *  B,
uint8_t  n 
)

Definition at line 42 of file matrix_alg.cpp.

Referenced by is_negative(), mat_inverse(), mat_LU_decompose(), and test_matrix_inverse().

Here is the caller graph for this function:

◆ MAX()

template<typename A , typename B >
static auto MAX ( const A one,
const B two 
) -> decltype(one > two ? one : two)
inlinestatic

Definition at line 202 of file AP_Math.h.

Referenced by AP_PitchController::_get_coordination_rate_offset(), AP_PitchController::_get_rate_out(), AP_RollController::_get_rate_out(), AP_InertialSensor_PX4::_get_sample(), AP_InertialSensor_PX4::_new_accel_sample(), AP_InertialSensor_PX4::_new_gyro_sample(), HALSITL::SITL_State::_simulator_servos(), ChibiOS::I2CDevice::_transfer(), HALSITL::SITL_State::_update_gps_ubx(), AP_TECS::_update_pitch(), AP_TECS::_update_speed(), AP_TECS::_update_throttle_with_airspeed(), AC_WPNav::AC_WPNav(), AC_Avoid::adjust_velocity_circle_fence(), AC_Avoid::adjust_velocity_polygon(), AC_WPNav::advance_wp_target_along_track(), AP_Landing_Deepstall::build_approach_path(), AC_Loiter::calc_desired_velocity(), AC_Circle::calc_velocities(), NavEKF2_core::calcGpsGoodForFlight(), NavEKF3_core::calcGpsGoodForFlight(), NavEKF3_core::calcOutputStates(), NavEKF2_core::CalcRangeBeaconPosDownOffset(), NavEKF3_core::CalcRangeBeaconPosDownOffset(), AP_TempCalibration::calculate_correction(), NavEKF2_core::ConstrainStates(), NavEKF3_core::ConstrainStates(), AC_PrecLand::construct_pos_meas_using_rangefinder(), NavEKF3_core::controlMagYawReset(), NavEKF2_core::correctEkfOriginHeight(), NavEKF3_core::correctEkfOriginHeight(), NavEKF2_core::errorScore(), NavEKF3_core::errorScore(), NavEKF2_core::EstimateTerrainOffset(), NavEKF3_core::EstimateTerrainOffset(), AC_PID_2D::filt_d_hz(), AC_PID_2D::filt_hz(), AC_PI_2D::filt_hz(), AC_PID::filt_hz(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), NavEKF2_core::fuseEulerYaw(), NavEKF3_core::fuseEulerYaw(), NavEKF2_core::FuseMagnetometer(), NavEKF3_core::FuseMagnetometer(), NavEKF2_core::FuseOptFlow(), NavEKF3_core::FuseOptFlow(), NavEKF2_core::FuseRngBcn(), NavEKF3_core::FuseRngBcn(), NavEKF2_core::FuseRngBcnStatic(), NavEKF3_core::FuseRngBcnStatic(), NavEKF2_core::FuseVelPosNED(), NavEKF3_core::FuseVelPosNED(), AR_AttitudeControl::get_accel_max(), AC_Fence::get_breach_distance(), AC_Avoid::get_proximity_roll_pitch_pct(), AP_Winch::get_rate_max(), AP_YawController::get_servo_out(), AP_SteerController::get_steering_out_rate(), AC_AttitudeControl_Sub::get_throttle_avg_max(), AC_AttitudeControl_Multi::get_throttle_avg_max(), AP_Proximity_SITL::get_upward_distance(), NavEKF3_core::getBodyFrameOdomDebug(), NavEKF2_core::getEkfControlLimits(), NavEKF3_core::getEkfControlLimits(), NavEKF2_core::getFlowDebug(), NavEKF3_core::getFlowDebug(), NavEKF2_core::getHeightControlLimit(), NavEKF3_core::getHeightControlLimit(), NavEKF2_core::getVariances(), NavEKF3_core::getVariances(), ChibiOS::RCOutput::init(), NavEKF2_core::InitialiseVariables(), NavEKF3_core::InitialiseVariables(), AC_AttitudeControl::input_shaping_angle(), AC_PosControl::lean_angles_to_accel(), AP_TempCalibration::learn_calibration(), AP_L1_Control::loiter_radius(), loop(), AP_MotorsMatrix::output_armed_stabilizing(), AP_MotorsCoax::output_armed_stabilizing(), AP_MotorsTri::output_armed_stabilizing(), AP_MotorsSingle::output_armed_stabilizing(), AP_Landing_Deepstall::predict_travel_distance(), AP_GPS_SBF::process_message(), AP_Airspeed::read(), AP_BattMonitor_SMBus::read_remaining_capacity(), NavEKF2_core::readBaroData(), NavEKF3_core::readBaroData(), NavEKF2_core::readDeltaAngle(), NavEKF2_core::readDeltaVelocity(), NavEKF3_core::readDeltaVelocity(), NavEKF2_core::readGpsData(), NavEKF3_core::readGpsData(), NavEKF2_core::readIMUData(), NavEKF3_core::readIMUData(), NavEKF2_core::readRangeFinder(), NavEKF3_core::readRangeFinder(), NavEKF2_core::realignYawGPS(), NavEKF3_core::realignYawGPS(), SITL::XPlane::receive_data(), NavEKF2_core::ResetHeight(), NavEKF3_core::ResetHeight(), NavEKF2_core::ResetPosition(), NavEKF3_core::ResetPosition(), NavEKF2_core::ResetVelocity(), NavEKF3_core::ResetVelocity(), AC_PrecLand::run_estimator(), run_test(), AC_Loiter::sanity_check_params(), NavEKF2_core::SelectFlowFusion(), NavEKF3_core::SelectFlowFusion(), NavEKF2_core::selectHeightForFusion(), NavEKF3_core::selectHeightForFusion(), AC_AttitudeControl_Sub::set_throttle_out(), AC_AttitudeControl_Multi::set_throttle_out(), NavEKF3_core::setup_core(), AP_InertialSensor_Invensense::start(), AP_Baro_SITL::temperature_adjustment(), Airspeed_Calibration::update(), AP_SBusOut::update(), AC_Circle::update(), AC_Sprayer::update(), AP_Airspeed::update_calibration(), AP_MotorsMulticopter::update_lift_max_from_batt_voltage(), AP_L1_Control::update_loiter(), AP_TECS::update_pitch_throttle(), AP_RangeFinder_Backend::update_pre_arm_check(), AP_BattMonitor_Backend::update_resistance_estimate(), AP_Landing_Deepstall::update_steering(), AP_L1_Control::update_waypoint(), NavEKF2_core::updateTimingStatistics(), NavEKF3_core::updateTimingStatistics(), AP_BattMonitor::voltage_resting_estimate(), ChibiOS::RCOutput::write(), NavEKF2_core::writeOptFlowMeas(), and NavEKF3_core::writeOptFlowMeas().

Here is the caller graph for this function:

◆ MIN()

template<typename A , typename B >
static auto MIN ( const A one,
const B two 
) -> decltype(one < two ? one : two)
inlinestatic

Definition at line 196 of file AP_Math.h.

◆ norm()

template<typename T , typename U , typename... Params>
float norm ( const T  first,
const U  second,
const Params...  parameters 
)

Definition at line 190 of file AP_Math.h.

Referenced by AP_InertialSensor::_acal_save_calibrations(), AP_InertialSensor::_calculate_trim(), AP_GPS_UBLOX::_parse_gps(), HALSITL::SITL_State::_update_gps_mtk(), HALSITL::SITL_State::_update_gps_mtk16(), HALSITL::SITL_State::_update_gps_mtk19(), HALSITL::SITL_State::_update_gps_nmea(), HALSITL::SITL_State::_update_gps_nova(), HALSITL::SITL_State::_update_gps_ubx(), AP_AHRS_DCM::_yaw_gain(), AC_WPNav::advance_spline_target_along_track(), AC_WPNav::advance_wp_target_along_track(), NavEKF2_core::alignMagStateDeclination(), NavEKF3_core::alignMagStateDeclination(), AP_Mount_Backend::calc_angle_to_location(), AP_GPS::calc_blended_state(), NavEKF2_core::calcGpsGoodToAlign(), NavEKF3_core::calcGpsGoodToAlign(), AC_WPNav::calculate_wp_leash_length(), NavEKF2_core::correctEkfOriginHeight(), NavEKF3_core::correctEkfOriginHeight(), AP_AHRS_DCM::drift_correction(), NavEKF2_core::EstimateTerrainOffset(), NavEKF3_core::EstimateTerrainOffset(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), AC_Circle::get_closest_point_on_circle(), get_distance(), Location_Class::get_distance(), get_horizontal_distance_cm(), AC_PosControl::get_horizontal_error(), AC_PosControl::get_stopping_point_xy(), AC_WPNav::get_wp_distance_to_destination(), AP_GPS_MAV::handle_msg(), Vector2< int32_t >::length(), Vector3< int32_t >::length(), AC_PosControl::limit_vector_length(), AP_MotorsHeli_Single::move_actuators(), AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(), AP_AHRS_DCM::reset(), AC_PosControl::run_xy_controller(), NavEKF2_core::selectHeightForFusion(), NavEKF3_core::selectHeightForFusion(), SITL::ADSB::send_report(), AP_GPS::setHIL(), AC_PosControl::sqrt_controller(), TEST(), Airspeed_Calibration::update(), AC_Sprayer::update(), NavEKF2_core::UpdateStrapdownEquationsNED(), and NavEKF3_core::UpdateStrapdownEquationsNED().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ nsec_to_hz()

uint32_t nsec_to_hz ( uint32_t  nsec)
inline

Definition at line 212 of file AP_Math.h.

Referenced by Linux::PWM_Sysfs_Base::get_freq().

Here is the caller graph for this function:

◆ nsec_to_usec()

uint32_t nsec_to_usec ( uint32_t  nsec)
inline

Definition at line 222 of file AP_Math.h.

Referenced by Linux::RCOutput_Sysfs::read().

Here is the caller graph for this function:

◆ radians()

static constexpr float radians ( float  deg)
inlinestatic

Definition at line 158 of file AP_Math.h.

Referenced by AP_InertialSensor::_acal_save_calibrations(), AP_InertialSensor::_calculate_trim(), SITL::Calibration::_calibration_poses(), AP_InertialSensor_BMI160::_configure_gyro(), AP_PitchController::_get_coordination_rate_offset(), HALSITL::SITL_State::_output_to_flightgear(), HALSITL::SITL_State::_update_gps(), HALSITL::SITL_State::_update_rangefinder(), OpticalFlow_backend::_yawAngleRad(), AP_MotorsMatrix::add_motor(), AP_Avoidance::add_obstacle(), SITL::Aircraft::Aircraft(), AP_Mount_Backend::angle_input_rad(), AP_AHRS_View::AP_AHRS_View(), AC_AttitudeControl::attitude_controller_run_quat(), AC_Loiter::calc_desired_velocity(), SITL::SimRover::calc_lat_accel(), NavEKF2_core::calcEarthRateNED(), NavEKF3_core::calcEarthRateNED(), SITL::Frame::calculate_forces(), SITL::Submarine::calculate_forces(), SITL::Motor::calculate_forces(), AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors(), AP_MotorsHeli_Dual::calculate_roll_pitch_collective_factors(), AP_MotorsHeli_Single::calculate_roll_pitch_collective_factors(), NavEKF2_core::checkGyroCalStatus(), NavEKF3_core::checkGyroCalStatus(), AP_Beacon_Backend::correct_for_orient_yaw(), NavEKF2_core::CovarianceInit(), NavEKF3_core::CovarianceInit(), AP_GPS_Backend::fill_3d_velocity(), AP_InertialSensor_SITL::generate_accel(), AP_InertialSensor_SITL::generate_gyro(), AC_AttitudeControl::get_accel_pitch_max_radss(), AC_AttitudeControl::get_accel_roll_max_radss(), AC_AttitudeControl::get_accel_yaw_max_radss(), AP_Follow::get_offsets_ned(), AC_Avoid::get_proximity_roll_pitch_pct(), AC_AttitudeControl_Heli::get_roll_trim_rad(), AC_AttitudeControl::get_slew_yaw_rads(), AR_AttitudeControl::get_steering_out_rate(), AP_AHRS::groundspeed_vector(), SITL::Helicopter::Helicopter(), AP_Proximity_Backend::init_boundary(), AC_Loiter::init_target(), AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(), AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(), AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(), AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(), AC_AttitudeControl::input_quaternion(), AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(), AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(), AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(), AC_AttitudeControl::input_shaping_rate_predictor(), AP_Arming::ins_checks(), location_update(), AP_L1_Control::loiter_radius(), SITL::MultiCopter::MultiCopter(), AP_MotorsTri::output_armed_stabilizing(), AP_MotorsTri::output_to_motors(), AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(), AP_Landing_Deepstall::predict_travel_distance(), CompassLearn::process_sample(), AC_AttitudeControl::rate_bf_pitch_target(), AC_AttitudeControl::rate_bf_roll_target(), AC_AttitudeControl::rate_bf_yaw_target(), NavEKF3_core::realignYawGPS(), SITL::XPlane::receive_data(), AP_InertialSensor::register_gyro(), NavEKF2_core::resetGyroBias(), NavEKF3_core::resetGyroBias(), AC_PrecLand::retrieve_los_meas(), SITL::JSBSim::send_servos(), AP_Mount_Backend::set_angle_targets(), Compass::set_initial_location(), AC_Loiter::set_pilot_desired_acceleration(), Compass::set_use_for_yaw(), NavEKF3_core::setWindMagStateLearningMode(), AC_AttitudeControl::shift_ef_yaw_target(), SITL::SITL::simstate_send(), test_euler(), SITL::SimRover::turn_circle(), AP_OpticalFlow_SITL::update(), SITL::Gimbal::update(), SITL::Tracker::update(), SITL::Helicopter::update(), SITL::SimRover::update(), SITL::Balloon::update(), SITL::SingleCopter::update(), SITL::FlightAxis::update(), SITL::Aircraft::update_dynamics(), AP_L1_Control::update_heading_hold(), AP_TECS::update_pitch_throttle(), AP_AHRS_NavEKF::update_SITL(), AP_Landing_Deepstall::update_steering(), AP_Mount_Backend::update_targets_from_rc(), AP_L1_Control::update_waypoint(), SITL::Aircraft::update_wind(), and AP_Landing::wind_alignment().

Here is the caller graph for this function:

◆ rand_float()

float rand_float ( void  )

Definition at line 224 of file AP_Math.cpp.

Referenced by AP_Baro_SITL::_timer(), HALSITL::SITL_State::_update_airspeed(), HALSITL::SITL_State::_update_rangefinder(), AP_InertialSensor_SITL::generate_accel(), AP_InertialSensor_SITL::generate_gyro(), rand_vec3f(), and usec_to_hz().

Here is the caller graph for this function:

◆ rand_vec3f()

Vector3f rand_vec3f ( void  )

Definition at line 229 of file AP_Math.cpp.

Referenced by AP_Compass_SITL::_timer(), and usec_to_hz().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ safe_asin()

template<typename T >
float safe_asin ( const T  v)

Definition at line 43 of file AP_Math.cpp.

Referenced by Quaternion::get_euler_pitch(), is_negative(), AP_MotorsTri::output_armed_stabilizing(), Matrix3< float >::to_euler(), and AP_AHRS::update_AOA_SSA().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ safe_sqrt()

template<typename T >
float safe_sqrt ( const T  v)

◆ sq() [1/2]

template<typename T >
float sq ( const T  val)

Definition at line 170 of file AP_Math.h.

Referenced by AP_InertialSensor::_acal_save_calibrations(), AP_Airspeed_SDP3X::_correct_pressure(), AP_SmartRTL::add_point(), AC_WPNav::advance_spline_target_along_track(), AC_WPNav::advance_wp_target_along_track(), CompassCalibrator::calc_mean_squared_residuals(), AccelCalibrator::calc_mean_squared_residuals(), NavEKF2_core::calcOutputStates(), NavEKF3_core::calcOutputStates(), NavEKF2_core::calcQuatAndFieldStates(), NavEKF3_core::calcQuatAndFieldStates(), NavEKF2_core::CalcRangeBeaconPosDownOffset(), NavEKF3_core::CalcRangeBeaconPosDownOffset(), AP_TempCalibration::calculate_p_range(), NavEKF3_core::checkAttitudeAlignmentStatus(), NavEKF2_core::checkGyroCalStatus(), NavEKF3_core::checkGyroCalStatus(), Vector2< int32_t >::circle_segment_intersection(), NavEKF2_core::ConstrainVariances(), NavEKF3_core::ConstrainVariances(), AC_AttitudeControl::control_monitor_filter_pid(), NavEKF3_core::controlMagYawReset(), NavEKF2_core::correctEkfOriginHeight(), NavEKF3_core::correctEkfOriginHeight(), NavEKF2_core::CovarianceInit(), NavEKF3_core::CovarianceInit(), NavEKF2_core::CovariancePrediction(), NavEKF2_core::detectFlight(), NavEKF3_core::detectFlight(), NavEKF2_core::EstimateTerrainOffset(), NavEKF3_core::EstimateTerrainOffset(), CompassCalibrator::fit_acceptable(), Quaternion::from_axis_angle_fast(), NavEKF2_core::FuseAirspeed(), NavEKF3_core::FuseAirspeed(), NavEKF3_core::FuseBodyVel(), SoloGimbalEKF::fuseCompass(), NavEKF2_core::FuseDeclination(), NavEKF3_core::FuseDeclination(), NavEKF2_core::fuseEulerYaw(), NavEKF3_core::fuseEulerYaw(), NavEKF2_core::FuseMagnetometer(), NavEKF3_core::FuseMagnetometer(), NavEKF2_core::FuseOptFlow(), NavEKF3_core::FuseOptFlow(), NavEKF2_core::FuseRngBcn(), NavEKF3_core::FuseRngBcn(), NavEKF2_core::FuseRngBcnStatic(), NavEKF3_core::FuseRngBcnStatic(), NavEKF2_core::FuseSideslip(), NavEKF3_core::FuseSideslip(), SoloGimbalEKF::fuseVelocity(), NavEKF2_core::FuseVelPosNED(), NavEKF3_core::FuseVelPosNED(), AP_Baro::get_air_density_ratio(), AR_AttitudeControl::get_stopping_distance(), AC_Avoid::get_stopping_distance(), NavEKF2_core::healthy(), NavEKF3_core::healthy(), Quaternion::length(), location_path_proportion(), AP_L1_Control::loiter_radius(), norm(), SoloGimbalEKF::predictCovariance(), NavEKF2_core::readGpsData(), NavEKF3_core::readGpsData(), NavEKF2_core::readRngBcnData(), NavEKF3_core::readRngBcnData(), NavEKF2_core::realignYawGPS(), NavEKF3_core::realignYawGPS(), NavEKF2_core::resetGyroBias(), NavEKF3_core::resetGyroBias(), NavEKF2_core::ResetHeight(), NavEKF3_core::ResetHeight(), NavEKF2_core::ResetPosition(), NavEKF3_core::ResetPosition(), NavEKF2_core::ResetVelocity(), NavEKF3_core::ResetVelocity(), Quaternion::rotate_fast(), AC_PrecLand::run_estimator(), SoloGimbalEKF::RunEKF(), NavEKF2_core::SelectFlowFusion(), NavEKF3_core::SelectFlowFusion(), NavEKF2_core::selectHeightForFusion(), NavEKF3_core::selectHeightForFusion(), NavEKF2_core::SelectMagFusion(), NavEKF3_core::SelectMagFusion(), AC_WPNav::set_spline_origin_and_destination(), AC_WPNav::set_wp_origin_and_destination(), NavEKF2_core::setAidingMode(), NavEKF2_core::setWindMagStateLearningMode(), NavEKF3_core::setWindMagStateLearningMode(), sq(), AC_AttitudeControl::sqrt_controller(), AC_PosControl::sqrt_controller(), AC_AttitudeControl::stopping_point(), TEST(), Quaternion::to_axis_angle(), AP_L1_Control::turn_distance(), Airspeed_Calibration::update(), and AP_Airspeed::update_calibration().

Here is the caller graph for this function:

◆ sq() [2/2]

template<typename T , typename... Params>
float sq ( const T  first,
const Params...  parameters 
)

Definition at line 180 of file AP_Math.h.

Here is the call graph for this function:

◆ usec_to_hz()

uint32_t usec_to_hz ( uint32_t  usec)
inline

Definition at line 232 of file AP_Math.h.

Here is the call graph for this function:

◆ usec_to_nsec()

uint32_t usec_to_nsec ( uint32_t  usec)
inline

Definition at line 217 of file AP_Math.h.

Referenced by Linux::RCOutput_Sysfs::push(), and Linux::RCOutput_Sysfs::write().

Here is the caller graph for this function:

◆ wrap_180()

template<typename T >
float wrap_180 ( const T  angle,
float  unit_mod = 1 
)

Definition at line 96 of file AP_Math.cpp.

Referenced by AP_Proximity_Backend::convert_angle_to_sector(), AP_Beacon_Backend::correct_for_orient_yaw(), is_negative(), AP_Landing_Deepstall::verify_land(), and wrap_180_cd().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrap_180_cd()

template<typename T >
auto wrap_180_cd ( const T  angle) -> decltype(wrap_180(angle, 100.f))

Definition at line 111 of file AP_Math.cpp.

Referenced by AP_L1_Control::_prevent_indecision(), AR_AttitudeControl::get_forward_speed(), AP_L1_Control::get_yaw_sensor(), AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_euler_rate_yaw(), AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(), is_negative(), AP_L1_Control::nav_bearing_cd(), AP_L1_Control::target_bearing_cd(), TEST(), test_wrap_cd(), AP_L1_Control::update_heading_hold(), AP_AHRS_DCM::use_compass(), and AP_Landing_Deepstall::verify_land().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrap_2PI()

template<typename T >
float wrap_2PI ( const T  radian)

Definition at line 167 of file AP_Math.cpp.

Referenced by AP_Beacon::get_next_boundary_point(), AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(), is_negative(), AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(), CompassLearn::process_sample(), TEST(), and wrap_PI().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrap_360()

template<typename T >
float wrap_360 ( const T  angle,
float  unit_mod = 1 
)

◆ wrap_360_cd()

template<typename T >
auto wrap_360_cd ( const T  angle) -> decltype(wrap_360(angle, 100.f))

Definition at line 140 of file AP_Math.cpp.

Referenced by is_negative(), DataFlash_Class::Log_Write_AHRS2(), DataFlash_Class::Log_Write_POS(), SITL::SITL::Log_Write_SIMSTATE(), SITL::ADSB::send_report(), TEST(), and test_wrap_cd().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ wrap_PI()

template<typename T >
float wrap_PI ( const T  radian)