PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Namespaces | |
trajectory | |
Classes | |
class | LowPassFilter2p |
class | LowPassFilter2pVector3f |
Functions | |
template<typename T > | |
int | sign (T val) |
template<typename T > | |
int | signNoZero (T val) |
template<typename T > | |
const T | expo (const T &value, const T &e) |
template<typename T > | |
const T | superexpo (const T &value, const T &e, const T &g) |
template<typename T > | |
const T | deadzone (const T &value, const T &dz) |
template<typename T > | |
const T | expo_deadzone (const T &value, const T &e, const T &dz) |
template<typename T > | |
const T | gradual (const T &value, const T &x_low, const T &x_high, const T &y_low, const T &y_high) |
template<typename T > | |
const T | expontialFromLimits (const T &X_in, const T &Y_min, const T &Y_mid, const T &Y_max) |
template<typename _Tp > | |
constexpr _Tp | min (_Tp a, _Tp b) |
template<typename _Tp > | |
constexpr _Tp | max (_Tp a, _Tp b) |
template<typename _Tp > | |
constexpr _Tp | constrain (_Tp val, _Tp min_val, _Tp max_val) |
constexpr int16_t | constrainFloatToInt16 (float value) |
Constrain float values to valid values for int16_t. More... | |
template<typename _Tp > | |
constexpr bool | isInRange (_Tp val, _Tp min_val, _Tp max_val) |
template<typename T > | |
constexpr T | radians (T degrees) |
template<typename T > | |
constexpr T | degrees (T radians) |
bool | isZero (float val) |
Safe way to check if float is zero. More... | |
bool | isZero (double val) |
Safe way to check if double is zero. More... | |
template<typename _Tp > | |
_Tp | abs_t (_Tp val) |
template<typename _Tp > | |
const _Tp | goldensection (const _Tp &arg1, const _Tp &arg2, _Tp(*fun)(_Tp), const _Tp &tol) |
Variables | |
static constexpr double | GOLDEN_RATIO = 1.6180339887 |
_Tp math::abs_t | ( | _Tp | val | ) |
Definition at line 49 of file SearchMin.hpp.
Referenced by VelocitySmoothing::computeT2(), RoverPositionControl::control_position(), and goldensection().
constexpr _Tp math::constrain | ( | _Tp | val, |
_Tp | min_val, | ||
_Tp | max_val | ||
) |
Definition at line 66 of file Limits.hpp.
Referenced by FlightTaskAutoLineSmoothVel::_constrainOneSide(), FlightTaskAutoLineSmoothVel::_generateTrajectory(), FlightTaskAutoLine::_generateXYsetpoints(), TECS::_initialize_states(), FlightTaskAuto::_limitYawRate(), PositionControl::_positionController(), FlightTaskManualAltitude::_respectGroundSlowdown(), FlightTaskManualAltitude::_respectMaxAltitude(), FlightTaskManualPosition::_scaleSticks(), TECS::_update_pitch_setpoint(), TECS::_update_speed_setpoint(), TECS::_update_speed_states(), TECS::_update_throttle_setpoint(), PositionControl::_velocityController(), FixedwingPositionControl::airspeed_poll(), Ekf::calcExtVisRotMat(), Ekf::calcOptFlowBodyRateComp(), Ekf::calcOptFlowMeasVar(), RTL::calculate_return_alt_from_cone_half_angle(), FixedwingPositionControl::calculate_target_airspeed(), Ekf::calculateOutputStates(), AirspeedValidator::check_load_factor(), Commander::check_posvel_validity(), Radar::collect(), Ekf::collect_imu(), InnovationLpf::computeAlphaFromDtAndTauInv(), constrainFloatToInt16(), Ekf::constrainStates(), RoverPositionControl::control_attitude(), ECL_YawController::control_attitude_impl_openloop(), ECL_YawController::control_bodyrate(), ECL_RollController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_PitchController::control_bodyrate(), FixedwingPositionControl::control_landing(), RoverPositionControl::control_position(), FixedwingPositionControl::control_position(), FixedwingPositionControl::control_takeoff(), RoverPositionControl::control_velocity(), Ekf::controlGpsFusion(), Ekf::controlHeightFusion(), TAP_ESC::cycle(), deadzone(), expo(), expontialFromLimits(), Ekf2::filter_altitude_ellipsoid(), Ekf::fixCovarianceErrors(), Ekf::fuseAirspeed(), Ekf::fuseDeclination(), Ekf::fuseGpsAntYaw(), Ekf::fuseHeading(), Ekf::fuseVelPosHeight(), FixedwingAttitudeControl::get_airspeed_and_update_scaling(), get_lookup_table_index(), RCUpdate::RCUpdate::get_rc_value(), get_table_data(), WeatherVane::get_weathervane_yawrate(), runwaytakeoff::RunwayTakeoff::getRoll(), Ekf::gps_is_good(), Commander::handle_command_motor_test(), MavlinkReceiver::handle_message_manual_control(), Ekf::initialiseCovariance(), PX4IO::io_set_control_state(), MissionBlock::is_mission_item_reached(), map_projection_project(), HelicopterMixer::mix(), MultirotorMixer::mix(), ECL_L1_Pos_Controller::navigate_heading(), ECL_L1_Pos_Controller::navigate_loiter(), ECL_L1_Pos_Controller::navigate_waypoints(), FollowTarget::on_activation(), Standard::parameters_update(), MulticopterPositionControl::parameters_update(), VtolAttitudeControl::parameters_update(), Ekf::predictCovariance(), Ekf::predictState(), Sih::read_motors(), Ekf::realignYawGPS(), Ekf::resetWindCovariance(), MulticopterRateControl::Run(), MulticopterAttitudeControl::Run(), RCUpdate::RCUpdate::Run(), AttitudeEstimatorQ::Run(), FixedwingAttitudeControl::Run(), FixedwingPositionControl::Run(), Heater::Run(), Ekf::runTerrainEstimator(), SimpleMixer::scale(), ECL_PitchController::set_bodyrate_setpoint(), ECL_Controller::set_bodyrate_setpoint(), RCUpdate::RCUpdate::set_params_from_rc(), MultirotorMixer::set_thrust_factor(), MixerGroup::set_trims(), PX4IO::set_update_rate(), EstimatorInterface::setIMUData(), AttitudeControl::setProportionalGain(), FlightTaskOrbit::setRadius(), superexpo(), PX4IO::task_main(), FixedwingPositionControl::tecs_update_pitch_throttle(), InnovationLpf::update(), AttitudeControl::update(), AttitudeEstimatorQ::update(), PX4FMU::update_current_rate(), AirspeedValidator::update_EAS_scale(), Ekf2::update_gps_offsets(), Ekf2::update_mag_bias(), DShotOutput::update_params(), TECS::update_pitch_throttle(), Mavlink::update_rate_mult(), ECL_L1_Pos_Controller::update_roll_setpoint(), Tiltrotor::update_transition_state(), Standard::update_transition_state(), TECS::update_vehicle_state_estimates(), VelocitySmoothing::updateDurations(), RateControl::updateIntegral(), MixingOutput::updateOutputSlewrate(), and FixedwingAttitudeControl::vehicle_manual_poll().
constexpr int16_t math::constrainFloatToInt16 | ( | float | value | ) |
Constrain float values to valid values for int16_t.
Invalid values are just clipped to be in the range for int16_t.
Definition at line 73 of file Limits.hpp.
References constrain().
const T math::deadzone | ( | const T & | value, |
const T & | dz | ||
) |
Definition at line 112 of file Functions.hpp.
References constrain(), and sign().
Referenced by expo_deadzone().
constexpr T math::degrees | ( | T | radians | ) |
Definition at line 91 of file Limits.hpp.
References MATH_PI.
Referenced by CollisionPrevention::_addDistanceSensorData(), CollisionPrevention::_addObstacleSensorData(), CollisionPrevention::_calculateConstrainedSetpoint(), add_vector_to_global_position(), Navigator::check_traffic(), MavlinkMissionManager::format_mavlink_mission_item(), EstimatorInterface::get_mag_decl_deg(), map_projection_global_getref(), map_projection_reproject(), Sih::reconstruct_sensors_signals(), MavlinkStreamVFRHUD::send(), MavlinkStreamGPSRawInt::send(), MavlinkStreamGPS2Raw::send(), MavlinkStreamGlobalPositionInt::send(), MavlinkStreamNavControllerOutput::send(), MavlinkStreamMountOrientation::send(), CRSFTelemetry::send_gps(), TEST_F(), waypoint_from_heading_and_distance(), MavlinkStreamHighLatency2::write_attitude_sp(), MavlinkStreamHighLatency2::write_global_position(), and MavlinkStreamHighLatency2::write_wind_estimate().
const T math::expo | ( | const T & | value, |
const T & | e | ||
) |
Definition at line 71 of file Functions.hpp.
References constrain().
Referenced by expo_deadzone(), and superexpo().
const T math::expo_deadzone | ( | const T & | value, |
const T & | e, | ||
const T & | dz | ||
) |
Definition at line 123 of file Functions.hpp.
References deadzone(), and expo().
Referenced by FlightTaskManual::_evaluateSticks().
const T math::expontialFromLimits | ( | const T & | X_in, |
const T & | Y_min, | ||
const T & | Y_mid, | ||
const T & | Y_max | ||
) |
Definition at line 176 of file Functions.hpp.
References constrain().
Referenced by FlightTaskAutoLine::_setSpeedAtTarget().
|
inline |
Definition at line 56 of file SearchMin.hpp.
References abs_t().
Referenced by SearchMinTest::_init_inputs(), SearchMinTest::_init_inputs_flipped(), SearchMinTest::_init_inputs_negative(), SearchMinTest::_init_tol_larger_than_range(), SearchMinTest::_init_tol_larger_than_range_flipped(), and SearchMinTest::_no_extremum().
const T math::gradual | ( | const T & | value, |
const T & | x_low, | ||
const T & | x_high, | ||
const T & | y_low, | ||
const T & | y_high | ||
) |
Definition at line 139 of file Functions.hpp.
Referenced by FlightTaskAutoLine::_generateAltitudeSetpoints(), FlightTaskAutoMapper::_generateTakeoffSetpoints(), FlightTaskManualAltitude::_respectGroundSlowdown(), Battery::estimateRemaining(), Simulator::handle_message_hil_sensor(), and FixedwingAttitudeControl::Run().
constexpr bool math::isInRange | ( | _Tp | val, |
_Tp | min_val, | ||
_Tp | max_val | ||
) |
Definition at line 79 of file Limits.hpp.
|
inline |
Safe way to check if float is zero.
Definition at line 97 of file Limits.hpp.
References f(), and FLT_EPSILON.
|
inline |
Safe way to check if double is zero.
Definition at line 103 of file Limits.hpp.
constexpr _Tp math::max | ( | _Tp | a, |
_Tp | b | ||
) |
Definition at line 60 of file Limits.hpp.
Referenced by FlightTaskManualAltitude::_applyYawspeedFilter(), CollisionPrevention::_calculateConstrainedSetpoint(), FlightTaskAutoLine::_generateXYsetpoints(), BezierQuadTest::_get_arc_length(), land_detector::MulticopterLandDetector::_get_ground_contact_state(), BezierQuadTest::_set_bez_from_vel(), TECS::_update_pitch_setpoint(), TECS::_update_speed_states(), CollisionPrevention::_updateObstacleMap(), sensors::VotedSensorsUpdate::calcMagInconsistency(), RTL::calculate_return_alt_from_cone_half_angle(), Ekf::calculate_synthetic_mag_z_measurement(), FixedwingPositionControl::calculate_target_airspeed(), UavcanServers::cb_enumeration_getset(), AirspeedValidator::check_airspeed_innovation(), SimpleAnalyzer::check_limits(), runwaytakeoff::RunwayTakeoff::climbout(), LidarLiteI2C::collect(), VelocitySmoothing::computeT1(), VelocitySmoothing::computeT2(), VelocitySmoothing::computeT3(), ECL_YawController::control_bodyrate(), ECL_RollController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_PitchController::control_bodyrate(), FixedwingPositionControl::control_position(), FixedwingPositionControl::control_takeoff(), Mission::do_abort_landing(), Battery::estimateRemaining(), WindEstimator::fuse_airspeed(), Ekf::fuseGpsAntYaw(), Ekf::fuseHeading(), Ekf::fuseMag(), Ekf::fuseOptFlow(), Ekf::fuseVelPosHeight(), Takeoff::generateInitialRampValue(), FixedwingAttitudeControl::get_airspeed_and_update_scaling(), BATT_SMBUS::get_cell_voltages(), Ekf::get_ekf_gpos_accuracy(), Ekf::get_ekf_lpos_accuracy(), Ekf::get_ekf_vel_accuracy(), Ekf::get_innovation_test_status(), MissionBlock::get_time_inside(), Landingslope::getFlareCurveRelativeAltitudeSave(), runwaytakeoff::RunwayTakeoff::getMaxPitch(), runwaytakeoff::RunwayTakeoff::getMinPitch(), Simulator::handle_message_hil_sensor(), EstimatorInterface::initialise_interface(), Ekf::initialiseFilter(), MulticopterPositionControl::limit_altitude(), px4::logger::LogWriterFile::LogWriterFile(), UavcanEscController::max_output_value(), MissionBlock::mission_item_to_position_setpoint(), ECL_L1_Pos_Controller::navigate_loiter(), ECL_L1_Pos_Controller::navigate_waypoints(), UavcanGnssBridge::process_fixx(), MPL3115A2_I2C::reset(), BlockLocalPositionEstimator::Run(), WindEstimator::run_sanity_checks(), uavcan_stm32::CanIface::send(), uavcan_kinetis::CanIface::send(), MavlinkStreamVFRHUD::send(), ECL_Controller::set_integrator_max(), SF1XX::set_maximum_distance(), SF0X::set_maximum_distance(), UavcanNode::set_param(), RTL::set_rtl_item(), EstimatorInterface::setBaroData(), EstimatorInterface::setGpsData(), PositionControl::setPositionGains(), FixedwingPositionControl::tecs_update_pitch_throttle(), RCUpdate::update_parameters(), RateControl::updateIntegral(), FlightTaskAutoMapper::updateParams(), and FlightTaskAutoMapper2::updateParams().
constexpr _Tp math::min | ( | _Tp | a, |
_Tp | b | ||
) |
Definition at line 54 of file Limits.hpp.
Referenced by CollisionPrevention::_addDistanceSensorData(), CollisionPrevention::_calculateConstrainedSetpoint(), FlightTaskAutoLineSmoothVel::_constrainAbs(), FlightTaskAuto::_evaluateTriplets(), FlightTaskAutoLine::_generateXYsetpoints(), BezierQuadTest::_get_arc_length(), FlightTaskAutoLineSmoothVel::_getSpeedAtTarget(), FlightTaskManualAltitude::_respectMaxAltitude(), ManualSmoothingXY::_setStateAcceleration(), TECS::_update_pitch_setpoint(), CollisionPrevention::_updateObstacleMap(), PositionControl::_velocityController(), Mission::altitude_sp_foh_update(), build_gps_response(), UavcanServers::cb_enumeration_getset(), SimpleAnalyzer::check_limits(), runwaytakeoff::RunwayTakeoff::climbout(), uavcan_kinetis::CanIface::computeTimings(), ECL_YawController::control_bodyrate(), ECL_WheelController::control_bodyrate(), ECL_RollController::control_bodyrate(), ECL_PitchController::control_bodyrate(), FixedwingPositionControl::control_landing(), FixedwingPositionControl::control_position(), convert_to_degrees_minutes_seconds(), StraightLine::generateSetpoints(), BATT_SMBUS::get_cell_voltages(), get_lookup_table_index(), runwaytakeoff::RunwayTakeoff::getMinPitch(), MavlinkReceiver::handle_message_gps_rtcm_data(), EstimatorInterface::initialise_interface(), MulticopterPositionControl::parameters_update(), VtolAttitudeControl::parameters_update(), GPS::pollOrRead(), MicroBenchMatrix::random(), MicroBenchORB::random(), MicroBenchHRT::random(), MicroBenchMath::random(), SF1XX::set_minimum_distance(), SF0X::set_minimum_distance(), UavcanNode::set_param(), RTL::set_return_alt_min(), RTL::set_rtl_item(), PositionControl::setPositionGains(), ECL_L1_Pos_Controller::switch_distance(), AirspeedModule::task_spawn(), AttitudeEstimatorQ::update(), TemperatureCalibrationCommon< 3, 3 >::update(), RCUpdate::update_parameters(), FlightTask::updateInitialize(), RateControl::updateIntegral(), DShotOutput::updateOutputs(), VelocitySmoothing::updateTraj(), px4::logger::Logger::write_console_output(), px4::logger::LogWriterMavlink::write_message(), and px4::logger::LogWriterFile::write_message().
constexpr T math::radians | ( | T | degrees | ) |
Definition at line 85 of file Limits.hpp.
References MATH_PI.
Referenced by CollisionPrevention::_adaptSetpointDirection(), CollisionPrevention::_calculateConstrainedSetpoint(), FlightTaskAutoMapper::_generateLandSetpoints(), land_detector::MulticopterLandDetector::_get_maybe_landed_state(), FlightTaskAuto::_limitYawRate(), FlightTaskAutoMapper2::_prepareLandSetpoints(), FlightTaskManualAltitude::_scaleSticks(), FlightTask::_setDefaultConstraints(), FlightTaskManualAltitude::activate(), FlightTaskManualPosition::activate(), add_vector_to_global_position(), ADIS16477::ADIS16477(), ADIS16497::ADIS16497(), RTL::calculate_return_alt_from_cone_half_angle(), VtolType::check_quadchute_condition(), Ekf::collect_gps(), Ekf::constrainStates(), ECL_YawController::control_attitude_impl_openloop(), FixedwingPositionControl::control_landing(), FixedwingPositionControl::control_position(), FixedwingPositionControl::control_takeoff(), Ekf::controlFusionModes(), Ekf::controlOpticalFlowFusion(), FixedwingPositionControl::do_takeoff_help(), FixedwingAttitudeControl::FixedwingAttitudeControl(), Ekf::fuseGpsAntYaw(), MulticopterAttitudeControl::generate_attitude_setpoint(), get_bearing_to_next_waypoint(), get_distance_to_next_waypoint(), ECL_L1_Pos_Controller::get_local_planar_vector(), get_rot_matrix(), get_rot_quaternion(), get_vector_to_next_waypoint(), get_vector_to_next_waypoint_fast(), FixedwingPositionControl::get_waypoint_heading_distance(), WeatherVane::get_weathervane_yawrate(), Navigator::get_yaw_threshold(), Landingslope::getFlareCurveRelativeAltitudeSave(), Landingslope::getLandingSlopeRelativeAltitudeSave(), Ekf::getMagDeclination(), runwaytakeoff::RunwayTakeoff::getPitch(), runwaytakeoff::RunwayTakeoff::getRoll(), MavlinkReceiver::handle_message_hil_gps(), MavlinkReceiver::handle_message_hil_state_quaternion(), TFMINI::init(), FixedwingPositionControl::init(), Ekf::limitDeclination(), map_projection_init_timestamped(), map_projection_project(), ECL_L1_Pos_Controller::navigate_waypoints(), GpsFailure::on_active(), FollowTarget::on_active(), Tailsitter::parameters_update(), Standard::parameters_update(), FixedwingAttitudeControl::parameters_update(), MulticopterRateControl::parameters_updated(), MulticopterAttitudeControl::parameters_updated(), Sih::parameters_updated(), VehicleAcceleration::ParametersUpdate(), VehicleAngularVelocity::ParametersUpdate(), MavlinkMissionManager::parse_mavlink_mission_item(), Ekf::resetGpsAntYaw(), Ekf::resetWindCovariance(), AttitudeEstimatorQ::Run(), FixedwingAttitudeControl::Run(), MulticopterPositionControl::Run(), GPS::run(), TEST_F(), AttitudeEstimatorQ::update_parameters(), FailureDetector::updateAttitudeStatus(), RateControl::updateIntegral(), FixedwingAttitudeControl::vehicle_manual_poll(), waypoint_from_heading_and_distance(), and RoverPositionControl::~RoverPositionControl().
int math::sign | ( | T | val | ) |
Definition at line 49 of file Functions.hpp.
References FLT_EPSILON.
Referenced by FlightTaskAuto::_compute_heading_from_2D_vector(), FlightTaskAutoLineSmoothVel::_constrainAbs(), PositionControl::_velocityController(), AttitudeControlConvergenceTest::adaptAntipodal(), VelocitySmoothing::computeDirection(), VelocitySmoothing::computeVelAtZeroAcc(), RoverPositionControl::control_position(), deadzone(), and FlightTaskOrbit::setRadius().
int math::signNoZero | ( | T | val | ) |
Definition at line 56 of file Functions.hpp.
Referenced by FlightTaskOrbit::sendTelemetry(), and AttitudeControl::update().
const T math::superexpo | ( | const T & | value, |
const T & | e, | ||
const T & | g | ||
) |
Definition at line 90 of file Functions.hpp.
References constrain(), and expo().
Referenced by MulticopterRateControl::Run().
|
static |
Definition at line 45 of file SearchMin.hpp.