PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <Dual.hpp>
Public Types | |
typedef Matrix< Type, M, 1 > | MatrixM1 |
Public Member Functions | |
Vector ()=default | |
Vector (const MatrixM1 &other) | |
Vector (const Type data_[M]) | |
template<size_t P, size_t Q> | |
Vector (const Slice< Type, M, 1, P, Q > &slice_in) | |
Type | operator() (size_t i) const |
Type & | operator() (size_t i) |
Type | dot (const MatrixM1 &b) const |
Type | operator* (const MatrixM1 &b) const |
Vector | operator* (Type b) const |
Type | norm () const |
Type | norm_squared () const |
Type | length () const |
void | normalize () |
Vector | unit () const |
Vector | unit_or_zero (const Type eps=Type(1e-5)) const |
Vector | normalized () const |
bool | longerThan (Type testVal) const |
Vector | sqrt () const |
Public Member Functions inherited from matrix::Matrix< Type, M, 1 > | |
Matrix ()=default | |
Matrix (const Type data_[M *N]) | |
Matrix (const Type data_[M][N]) | |
Matrix (const Matrix &other) | |
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 |
Matrix< Type, M, P > | operator* (const Matrix< Type, N, P > &other) const |
Matrix Operations. More... | |
Matrix< Type, M, N > | operator* (Type scalar) const |
Scalar 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+ (Type scalar) const |
Matrix< Type, M, N > | operator- (const Matrix< Type, M, N > &other) const |
Matrix< Type, M, N > | operator- () const |
Matrix< Type, M, N > | operator- (Type scalar) const |
void | operator+= (const Matrix< Type, M, N > &other) |
void | operator+= (Type scalar) |
void | operator-= (const Matrix< Type, M, N > &other) |
void | operator-= (Type scalar) |
void | operator*= (const Matrix< Type, N, P > &other) |
void | operator*= (Type scalar) |
Matrix< Type, M, N > | operator/ (Type scalar) const |
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 |
const Slice< Type, P, Q, M, N > | slice (size_t x0, size_t y0) const |
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 |
typedef Matrix<Type, M, 1> matrix::Vector< Type, M >::MatrixM1 |
Definition at line 23 of file Vector.hpp.
|
default |
Referenced by matrix::Vector< Type, 3 >::operator*(), and matrix::Vector< Type, 3 >::unit_or_zero().
|
inline |
Definition at line 27 of file Vector.hpp.
|
inlineexplicit |
Definition at line 32 of file Vector.hpp.
|
inline |
Definition at line 38 of file Vector.hpp.
|
inline |
Definition at line 55 of file Vector.hpp.
Referenced by CollisionPrevention::_calculateConstrainedSetpoint(), FlightTaskAutoLineSmoothVel::_generateTrajectory(), ControlMath::constrainXY(), main(), TEST_F(), and MatrixTest::vectorTests().
|
inline |
Definition at line 83 of file Vector.hpp.
Referenced by FlightTaskAuto::_compute_heading_from_2D_vector(), FlightTaskAutoLineSmoothVel::_generateHeadingAlongTraj(), FlightTaskAutoLineSmoothVel::_generateTrajectory(), FlightTaskAutoLine::_generateXYsetpoints(), FlightTaskAuto::_getCurrentState(), ManualSmoothingXY::_getIntention(), FlightTaskManualPosition::_scaleSticks(), FlightTaskAuto::_set_heading_from_mode(), ManualSmoothingXY::_setStateAcceleration(), FlightTaskManualAltitude::_updateSetpoints(), PositionControl::_velocityController(), ObstacleAvoidance::checkAvoidanceProgress(), ManualVelocitySmoothingXY::checkPositionLock(), ControlMath::constrainXY(), ControlMath::cross_sphere_line(), MatrixTest::dcmRenormTests(), WindEstimator::fuse_beta(), bezier::BezierQuad< Tp >::getArcLength(), main(), FollowTarget::on_active(), PrecLand::slewrate(), and ControlMath::thrustToAttitude().
|
inline |
Definition at line 107 of file Vector.hpp.
Referenced by main().
|
inline |
Definition at line 73 of file Vector.hpp.
Referenced by CollisionPrevention::_calculateConstrainedSetpoint(), matrix::AxisAngle< Type >::angle(), AttitudeControlConvergenceTest::checkConvergence(), BlockLocalPositionEstimator::flowCorrect(), matrix::Quaternion< Type >::from_axis_angle(), MulticopterAttitudeControl::generate_attitude_setpoint(), FlightTaskOrbit::generate_circle_approach_setpoints(), FlightTaskOrbit::generate_circle_setpoints(), StraightLine::generateSetpoints(), matrix::Vector< Type, 3 >::length(), main(), matrix::Vector< Type, 3 >::normalize(), TEST_F(), matrix::Vector< Type, 3 >::unit(), matrix::Vector< Type, 3 >::unit_or_zero(), and MatrixTest::vectorTests().
|
inline |
Definition at line 78 of file Vector.hpp.
Referenced by RoverPositionControl::control_position(), matrix::Vector< Type, 3 >::longerThan(), main(), and StraightLine::setLineFromTo().
|
inline |
Definition at line 87 of file Vector.hpp.
Referenced by FlightTaskAuto::_compute_heading_from_2D_vector(), ManualSmoothingXY::_getIntention(), FlightTaskManualAltitude::_updateSetpoints(), ControlMath::cross_sphere_line(), Sih::equations_of_motion(), WeatherVane::get_weathervane_yawrate(), MavlinkReceiver::handle_message_odometry(), main(), MatrixTest::run_tests(), TEST_F(), ControlMath::thrustToAttitude(), AttitudeControl::update(), Standard::update_mc_state(), and MatrixTest::vectorTests().
|
inline |
Definition at line 103 of file Vector.hpp.
Referenced by FlightTaskManualPosition::_scaleSticks(), ManualSmoothingXY::_velocitySlewRate(), ControlMath::constrainXY(), main(), ECL_L1_Pos_Controller::navigate_waypoints(), PrecLand::slewrate(), and TEST_F().
|
inline |
Definition at line 43 of file Vector.hpp.
|
inline |
Definition at line 49 of file Vector.hpp.
|
inline |
Definition at line 64 of file Vector.hpp.
Referenced by matrix::Vector3< Type >::operator*().
|
inline |
Definition at line 69 of file Vector.hpp.
|
inline |
Definition at line 111 of file Vector.hpp.
Referenced by control::BlockStats< float, n_y_lidar >::getStdDev(), main(), and MatrixTest::vectorTests().
|
inline |
Definition at line 91 of file Vector.hpp.
Referenced by matrix::AxisAngle< Type >::axis(), matrix::AxisAngle< Type >::AxisAngle(), main(), matrix::Vector< Type, 3 >::normalized(), and MatrixTest::run_tests().
|
inline |
Definition at line 95 of file Vector.hpp.
Referenced by FlightTaskAutoLineSmoothVel::_prepareSetpoints(), FlightTaskOrbit::generate_circle_approach_setpoints(), FlightTaskOrbit::generate_circle_setpoints(), StraightLine::generateSetpoints(), and main().