|
MFCPP
1.0
|
Corentin Chauvin-Hameau – 2019-2020
|
|
Coverage Path Planning for an underwater robot surveying a marine farm
|
|
Declaration of common functions. More...
#include "mf_common/EulerPose.h"#include <geometry_msgs/TransformStamped.h>#include <geometry_msgs/Pose.h>#include <geometry_msgs/Quaternion.h>#include <geometry_msgs/Point.h>#include <tf2/LinearMath/Matrix3x3.h>#include <tf2/LinearMath/Vector3.h>#include <tf2_geometry_msgs/tf2_geometry_msgs.h>#include <eigen3/Eigen/Dense>

Go to the source code of this file.
Namespaces | |
| mfcpp | |
Functions | |
| geometry_msgs::Pose | mfcpp::to_pose (const geometry_msgs::TransformStamped &transform) |
| Converts a TransformStamped message to a Pose message. More... | |
| template<class T > | |
| T | mfcpp::modulo_2pi (T angle) |
| Brings back an angle into [-pi, pi) More... | |
| float | mfcpp::distance2 (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
| Computes the square of the euclidean distance between two positions. More... | |
| float | mfcpp::distance (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
| Computes the the euclidean distance between two positions. More... | |
| float | mfcpp::distance (const geometry_msgs::Pose &p1, const geometry_msgs::Pose &p2) |
| Computes the the euclidean distance between the position of two poses. More... | |
| geometry_msgs::Pose | mfcpp::interpolate (const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2, float t) |
| Interpolates linearily two poses. More... | |
| tf2::Quaternion | mfcpp::slerp (const tf2::Quaternion &q0, const tf2::Quaternion &q1, float t) |
| Spherical Linear Interpolation of two quaternions. More... | |
| void | mfcpp::to_euler (const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw) |
| Converts a quaternion to Roll-Pitch-Yaw Euler angles. More... | |
| void | mfcpp::to_euler (const geometry_msgs::Quaternion &quat, double &roll, double &pitch, double &yaw) |
| Converts a quaternion to Roll-Pitch-Yaw Euler angles. More... | |
| void | mfcpp::to_quaternion (double roll, double pitch, double yaw, tf2::Quaternion &quat) |
| Converts Roll-Pitch-Yaw Euler angles to a quaternion. More... | |
| void | mfcpp::to_quaternion (double roll, double pitch, double yaw, geometry_msgs::Quaternion &quat) |
| Converts Roll-Pitch-Yaw Euler angles to a quaternion. More... | |
| void | mfcpp::to_quaternion (float x, float y, float z, float angle, geometry_msgs::Quaternion &quat) |
| Converts Axis-angle to a quaternion. More... | |
| template<class VectorT > | |
| void | mfcpp::get_orientation (float roll, float pitch, float yaw, VectorT &orientation) |
| Get orientation vector (x vector of the frame) given by Roll-Pitch-Yaw. More... | |
| void | mfcpp::diff_pose (const geometry_msgs::Pose &p1, const geometry_msgs::Pose &p2, geometry_msgs::Pose &diff) |
| Computes the difference between two poses. More... | |
| void | mfcpp::diff_pose (const geometry_msgs::Pose &p1, const geometry_msgs::Pose &p2, mf_common::EulerPose &diff) |
| Computes the difference between two poses. More... | |
| template<class T > | |
| void | mfcpp::fill_diag_mat (const std::vector< T > &v, Eigen::DiagonalMatrix< T, Eigen::Dynamic > &D) |
| Fills a Eigen DiagonalMatrix from a std::Vector. More... | |
| template<class T , class MatrixT > | |
| void | mfcpp::fill_diag_mat (const std::vector< T > &v, MatrixT &D) |
| Fills a Eigen matrix from a std::Vector. More... | |
1.8.11