|
Formula Student Autonomous Systems
The code for the main driverless system
|
Classes | |
| struct | AngleAndNorms |
| structure to store the angle formed between two vectors and their norms More... | |
Typedefs | |
| using | TwoDVector = common_lib::structures::Position |
Functions | |
| AngleAndNorms | angle_and_norms (const TwoDVector &vector1, const TwoDVector &vector2) |
| Function used to calculate the angle between two vectors and their norms. | |
| void | copy_eigen_sparse_matrix (const Eigen::SparseMatrix< float > &original, Eigen::SparseMatrix< float > ©) |
| double | normalize_angle (double angle) |
| Function to keep angle in [-Pi, Pi[ radians. | |
| double | get_wheel_velocity_from_rpm (const double rpm, const double wheel_diameter) |
| Function to get the translational velocity of a wheel from rpm and wheel diameter. | |
| Eigen::Matrix2d | get_rotation_matrix (const double angle) |
| Function to get the rotation matrix for a given angle. | |
| Eigen::Vector2d | cartesian_to_cylindrical (const Eigen::Vector2d &cartesian) |
| Function to convert cartesian coordinates to cylindrical coordinates. | |
| Eigen::VectorXd | global_to_local_coordinates (const Eigen::Vector3d &local_reference_frame, const Eigen::VectorXd &global_points) |
| Transform points from a global reference frame to a local reference frame. | |
| Eigen::VectorXd | local_to_global_coordinates (const Eigen::Vector3d &local_reference_frame, const Eigen::VectorXd &local_points) |
| Transform points from a local reference frame to a global reference frame. | |
| using common_lib::maths::TwoDVector = typedef common_lib::structures::Position |
Definition at line 10 of file angle_and_norms.hpp.
| common_lib::maths::AngleAndNorms common_lib::maths::angle_and_norms | ( | const TwoDVector & | vector1, |
| const TwoDVector & | vector2 | ||
| ) |
Function used to calculate the angle between two vectors and their norms.
| vector1 | 2d vector represented by a pair of doubles |
| vector2 | 2d vector represented by a pair of doubles |
Definition at line 4 of file angle_and_norms.cpp.

| Eigen::Vector2d common_lib::maths::cartesian_to_cylindrical | ( | const Eigen::Vector2d & | cartesian | ) |
Function to convert cartesian coordinates to cylindrical coordinates.
| cartesian | Coordinates in cartesian |
Definition at line 27 of file transformations.cpp.

| void common_lib::maths::copy_eigen_sparse_matrix | ( | const Eigen::SparseMatrix< float > & | original, |
| Eigen::SparseMatrix< float > & | copy | ||
| ) |
Definition at line 4 of file matrixes.cpp.
| Eigen::Matrix2d common_lib::maths::get_rotation_matrix | ( | const double | angle | ) |
Function to get the rotation matrix for a given angle.
| angle |
Definition at line 21 of file transformations.cpp.

| double common_lib::maths::get_wheel_velocity_from_rpm | ( | const double | rpm, |
| const double | wheel_diameter | ||
| ) |
Function to get the translational velocity of a wheel from rpm and wheel diameter.
Definition at line 17 of file transformations.cpp.

| Eigen::VectorXd common_lib::maths::global_to_local_coordinates | ( | const Eigen::Vector3d & | local_reference_frame, |
| const Eigen::VectorXd & | global_points | ||
| ) |
Transform points from a global reference frame to a local reference frame.
| local_reference_frame | coordinates of the local reference frame in the global reference frame [x, y, rotation angle] |
| global_points | points in the global reference frame in format [x1, y1, x2, y2, ...] |
Definition at line 33 of file transformations.cpp.


| Eigen::VectorXd common_lib::maths::local_to_global_coordinates | ( | const Eigen::Vector3d & | local_reference_frame, |
| const Eigen::VectorXd & | local_points | ||
| ) |
Transform points from a local reference frame to a global reference frame.
| local_reference_frame | coordinates of the local reference frame in the global reference frame [x, y, rotation angle] |
| local_points | points in the local reference frame in format [x1, y1, x2, y2, ...] |
Definition at line 51 of file transformations.cpp.


| double common_lib::maths::normalize_angle | ( | double | angle | ) |
Function to keep angle in [-Pi, Pi[ radians.
| angle |
Definition at line 7 of file transformations.cpp.
