PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <Matrix.hpp>
Public Member Functions | |
Matrix ()=default | |
Matrix (const Type data_[M *N]) | |
Matrix (const Type data_[M][N]) | |
Matrix (const Matrix &other) | |
template<size_t P, size_t Q> | |
Matrix (const Slice< Type, M, N, P, Q > &in_slice) | |
Type | operator() (size_t i, size_t j) const |
Accessors/ Assignment etc. More... | |
Type & | operator() (size_t i, size_t j) |
Matrix< Type, M, N > & | operator= (const Matrix< Type, M, N > &other) |
void | copyTo (Type dst[M *N]) const |
void | copyToColumnMajor (Type dst[M *N]) const |
template<size_t P> | |
Matrix< Type, M, P > | operator* (const Matrix< Type, N, P > &other) const |
Matrix Operations. More... | |
Matrix< Type, M, N > | emult (const Matrix< Type, M, N > &other) const |
Matrix< Type, M, N > | edivide (const Matrix< Type, M, N > &other) const |
Matrix< Type, M, N > | operator+ (const Matrix< Type, M, N > &other) const |
Matrix< Type, M, N > | operator- (const Matrix< Type, M, N > &other) const |
Matrix< Type, M, N > | operator- () const |
void | operator+= (const Matrix< Type, M, N > &other) |
void | operator-= (const Matrix< Type, M, N > &other) |
template<size_t P> | |
void | operator*= (const Matrix< Type, N, P > &other) |
Matrix< Type, M, N > | operator* (Type scalar) const |
Scalar Operations. More... | |
Matrix< Type, M, N > | operator/ (Type scalar) const |
Matrix< Type, M, N > | operator+ (Type scalar) const |
Matrix< Type, M, N > | operator- (Type scalar) const |
void | operator*= (Type scalar) |
void | operator/= (Type scalar) |
void | operator+= (Type scalar) |
void | operator-= (Type scalar) |
bool | operator== (const Matrix< Type, M, N > &other) const |
bool | operator!= (const Matrix< Type, M, N > &other) const |
void | write_string (char *buf, size_t n) const |
Misc. More... | |
void | print (FILE *stream=stdout) const |
Matrix< Type, N, M > | transpose () const |
Matrix< Type, N, M > | T () const |
template<size_t P, size_t Q> | |
const Slice< Type, P, Q, M, N > | slice (size_t x0, size_t y0) const |
template<size_t P, size_t Q> | |
Slice< Type, P, Q, M, N > | slice (size_t x0, size_t y0) |
const Slice< Type, 1, N, M, N > | row (size_t i) const |
Slice< Type, 1, N, M, N > | row (size_t i) |
const Slice< Type, M, 1, M, N > | col (size_t j) const |
Slice< Type, M, 1, M, N > | col (size_t j) |
void | setRow (size_t i, const Matrix< Type, N, 1 > &row_in) |
void | setCol (size_t j, const Matrix< Type, M, 1 > &column) |
void | setZero () |
void | zero () |
void | setAll (Type val) |
void | setOne () |
void | setNaN () |
void | setIdentity () |
void | identity () |
void | swapRows (size_t a, size_t b) |
void | swapCols (size_t a, size_t b) |
Matrix< Type, M, N > | abs () const |
Type | max () const |
Type | min () const |
bool | isAllNan () const |
Private Attributes | |
Type | _data [M][N] {} |
Definition at line 36 of file Matrix.hpp.
|
default |
|
inlineexplicit |
Definition at line 66 of file Matrix.hpp.
|
inlineexplicit |
Definition at line 71 of file Matrix.hpp.
|
inline |
Definition at line 76 of file Matrix.hpp.
|
inline |
Definition at line 82 of file Matrix.hpp.
|
inline |
Definition at line 492 of file Matrix.hpp.
|
inline |
Definition at line 395 of file Matrix.hpp.
Referenced by main(), and MatrixTest::matrixAssignmentTests().
|
inline |
Definition at line 400 of file Matrix.hpp.
|
inline |
Definition at line 115 of file Matrix.hpp.
Referenced by MulticopterAttitudeControl::generate_attitude_setpoint(), FlightTask::getPositionSetpoint(), MavlinkReceiver::handle_message_hil_state_quaternion(), Simulator::handle_message_hil_state_quaternion(), MavlinkReceiver::handle_message_odometry(), MavlinkReceiver::handle_message_set_attitude_target(), MavlinkReceiver::handle_message_vision_position_estimate(), main(), CollisionPrevention::modifySetpoint(), Simulator::publish_odometry_topic(), BlockLocalPositionEstimator::publishOdom(), Ekf2::Run(), MavlinkStreamAttitudeQuaternion::send(), ControlMath::thrustToAttitude(), Standard::update_mc_state(), Tailsitter::update_transition_state(), Standard::update_transition_state(), ObstacleAvoidance::updateAvoidanceDesiredSetpoints(), and ObstacleAvoidance::updateAvoidanceDesiredWaypoints().
|
inline |
Definition at line 120 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 171 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 157 of file Matrix.hpp.
Referenced by main(), MatrixTest::matrixMultTests(), MulticopterRateControl::parameters_updated(), MulticopterRateControl::Run(), AttitudeControl::update(), and RateControl::update().
|
inline |
Definition at line 457 of file Matrix.hpp.
Referenced by main(), MathlibTest::testMatrix3x3(), MathlibTest::testQuaternionfrom_dcm(), MathlibTest::testQuaternionfrom_euler(), and landing_target_estimator::KalmanFilter::update().
|
inline |
Definition at line 531 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 503 of file Matrix.hpp.
Referenced by matrix::max().
|
inline |
Definition at line 517 of file Matrix.hpp.
Referenced by main(), MatrixTest::matrixAssignmentTests(), and matrix::min().
|
inline |
Definition at line 321 of file Matrix.hpp.
|
inline |
Accessors/ Assignment etc.
Definition at line 97 of file Matrix.hpp.
|
inline |
Definition at line 102 of file Matrix.hpp.
|
inline |
Matrix Operations.
Definition at line 140 of file Matrix.hpp.
Referenced by matrix::Vector3< Type >::operator*().
|
inline |
Scalar Operations.
Definition at line 251 of file Matrix.hpp.
|
inline |
Definition at line 241 of file Matrix.hpp.
|
inline |
Definition at line 289 of file Matrix.hpp.
|
inline |
Definition at line 185 of file Matrix.hpp.
Referenced by matrix::Vector3< Type >::operator+().
|
inline |
Definition at line 270 of file Matrix.hpp.
|
inline |
Definition at line 228 of file Matrix.hpp.
|
inline |
Definition at line 306 of file Matrix.hpp.
|
inline |
Definition at line 199 of file Matrix.hpp.
|
inline |
Definition at line 214 of file Matrix.hpp.
Referenced by matrix::Vector3< Type >::operator-().
|
inline |
Definition at line 284 of file Matrix.hpp.
|
inline |
Definition at line 234 of file Matrix.hpp.
|
inline |
Definition at line 311 of file Matrix.hpp.
|
inline |
Definition at line 265 of file Matrix.hpp.
|
inline |
Definition at line 300 of file Matrix.hpp.
|
inline |
Definition at line 107 of file Matrix.hpp.
Referenced by matrix::SquareMatrix< Type, 3 >::operator=().
|
inline |
Definition at line 316 of file Matrix.hpp.
|
inline |
Definition at line 343 of file Matrix.hpp.
Referenced by main(), and MathlibTest::testMatrixNonsymmetric().
|
inline |
Definition at line 385 of file Matrix.hpp.
Referenced by matrix::collectDerivatives(), MatrixTest::dcmRenormTests(), AttitudeEstimatorQ::init_attq(), main(), MatrixTest::matrixAssignmentTests(), and matrix::Dcm< float >::renormalize().
|
inline |
Definition at line 390 of file Matrix.hpp.
|
inline |
Definition at line 426 of file Matrix.hpp.
Referenced by FlightTaskAuto::_evaluateTriplets(), FlightTask::_evaluateVehicleLocalPosition(), FlightTask::_resetSetpoints(), FlightTaskAuto::_set_heading_from_mode(), FlightTaskManualPosition::_updateSetpoints(), FlightTaskTransition::activate(), matrix::Matrix< float, n_x, n_u >::setNaN(), matrix::Matrix< float, n_x, n_u >::setOne(), and FlightTaskTransition::updateAccelerationEstimate().
|
inline |
Definition at line 411 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 447 of file Matrix.hpp.
Referenced by MatrixTest::filterTests(), matrix::Matrix< float, n_x, n_u >::identity(), main(), MatrixTest::matrixMultTests(), MatrixTest::setIdentityTests(), and TerrainEstimator::TerrainEstimator().
|
inline |
Definition at line 442 of file Matrix.hpp.
Referenced by matrix::constrain(), StraightLine::generateSetpoints(), ObstacleAvoidance::injectAvoidanceSetpoints(), main(), matrix::nans(), and ObstacleAvoidance::ObstacleAvoidance().
|
inline |
Definition at line 437 of file Matrix.hpp.
Referenced by matrix::ones().
|
inline |
Definition at line 405 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 416 of file Matrix.hpp.
Referenced by BlockLocalPositionEstimator::baroCorrect(), BlockLocalPositionEstimator::BlockLocalPositionEstimator(), Sih::equations_of_motion(), BlockLocalPositionEstimator::flowCorrect(), BlockLocalPositionEstimator::gpsCorrect(), WindEstimator::initialise(), BlockLocalPositionEstimator::initP(), BlockLocalPositionEstimator::initSS(), BlockLocalPositionEstimator::landCorrect(), BlockLocalPositionEstimator::landingTargetCorrect(), BlockLocalPositionEstimator::lidarCorrect(), main(), MatrixTest::matrixAssignmentTests(), TerrainEstimator::measurement_update(), BlockLocalPositionEstimator::mocapCorrect(), matrix::Matrix< float, n_x, n_u >::operator*(), TerrainEstimator::predict(), matrix::Matrix< float, n_x, n_u >::setIdentity(), BlockLocalPositionEstimator::sonarCorrect(), BlockLocalPositionEstimator::updateSSParams(), BlockLocalPositionEstimator::visionCorrect(), matrix::Matrix< float, n_x, n_u >::zero(), and matrix::zeros().
|
inline |
Definition at line 374 of file Matrix.hpp.
Referenced by main().
|
inline |
Definition at line 380 of file Matrix.hpp.
|
inline |
Definition at line 477 of file Matrix.hpp.
Referenced by main(), and MatrixTest::matrixAssignmentTests().
|
inline |
Definition at line 462 of file Matrix.hpp.
Referenced by main(), and MatrixTest::matrixAssignmentTests().
|
inline |
Definition at line 368 of file Matrix.hpp.
Referenced by matrix::kalman_correct(), and main().
|
inline |
Definition at line 353 of file Matrix.hpp.
Referenced by BlockLocalPositionEstimator::baroCorrect(), do_accel_calibration(), BlockLocalPositionEstimator::flowCorrect(), WindEstimator::fuse_airspeed(), WindEstimator::fuse_beta(), matrix::geninv(), BlockLocalPositionEstimator::gpsCorrect(), WindEstimator::initialise(), BlockLocalPositionEstimator::landCorrect(), BlockLocalPositionEstimator::landingTargetCorrect(), BlockLocalPositionEstimator::lidarCorrect(), main(), TerrainEstimator::measurement_update(), BlockLocalPositionEstimator::mocapCorrect(), TerrainEstimator::predict(), landing_target_estimator::KalmanFilter::predict(), BlockLocalPositionEstimator::predict(), Sih::reconstruct_sensors_signals(), MavlinkStreamOdometry::send(), matrix::Matrix< float, n_x, n_u >::setRow(), BlockLocalPositionEstimator::sonarCorrect(), matrix::Matrix< float, n_x, n_u >::T(), MatrixTest::transposeTests(), and BlockLocalPositionEstimator::visionCorrect().
|
inline |
Misc.
Functions
Definition at line 331 of file Matrix.hpp.
Referenced by main(), and matrix::Matrix< float, n_x, n_u >::print().
|
inline |
Definition at line 421 of file Matrix.hpp.
Referenced by Integrator::_reset(), FlightTaskFailsafe::activate(), FollowTarget::FollowTarget(), main(), TerrainEstimator::measurement_update(), FollowTarget::reset_target_validity(), RateControl::resetIntegral(), math::LowPassFilter2pVector3f::set_cutoff_frequency(), VehicleAcceleration::Start(), VehicleAngularVelocity::Start(), TerrainEstimator::TerrainEstimator(), TEST(), MathlibTest::testVector2(), MathlibTest::testVector3(), ControlMath::thrustToAttitude(), and landing_target_estimator::LandingTargetEstimator::update().
|
private |
Definition at line 47 of file Matrix.hpp.
Referenced by matrix::Matrix< float, n_x, n_u >::Matrix(), and matrix::Matrix< float, n_x, n_u >::operator=().