#include "tf/transform_datatypes.h"#include <string>#include <vector>#include <ostream>#include <stdint.h>#include <iostream>#include <cmath>#include <stdexcept>#include "duration.h"#include <sys/time.h>#include "serialized_message.h"#include "message_forward.h"#include <ros/time.h>#include <boost/utility/enable_if.hpp>#include <boost/type_traits/remove_const.hpp>#include <boost/type_traits/remove_reference.hpp>#include "message_traits.h"#include "ros/exception.h"#include <boost/array.hpp>#include <boost/call_traits.hpp>#include <boost/mpl/and.hpp>#include <boost/mpl/or.hpp>#include <boost/mpl/not.hpp>#include <cstring>#include "ros/builtin_message_traits.h"#include "ros/macros.h"#include <cstdio>#include <sstream>#include <log4cxx/logger.h>#include <boost/static_assert.hpp>#include <cassert>#include <string.h>#include <boost/shared_ptr.hpp>#include "ros/serialization.h"#include "ros/message_operations.h"#include "ros/message.h"#include "std_msgs/Header.h"#include "geometry_msgs/Vector3.h"#include "geometry_msgs/Quaternion.h"#include "geometry_msgs/Point.h"#include "btMatrix3x3.h"#include "ros/console.h"#include "Core"#include "src/Core/util/DisableMSVCWarnings.h"#include "SVD"#include "LU"#include <limits>#include "src/Geometry/OrthoMethods.h"#include "src/Geometry/EulerAngles.h"#include "src/Core/util/EnableMSVCWarnings.h"
Go to the source code of this file.
Namespaces | |
| namespace | tf |
Functions | |
| void | tf::RotationEigenToTF (const Eigen::eigen2_Quaterniond &k, tf::Quaternion &t) |
| Converts an Eigen Quaternion into a tf Quaternion. | |
| void | tf::RotationTFToEigen (const tf::Quaternion &t, Eigen::eigen2_Quaterniond &k) |
| Converts a tf Quaternion into an Eigen Quaternion. | |
| void | tf::TransformEigenToTF (const Eigen::eigen2_Transform3d &k, tf::Transform &t) |
| Converts an Eigen eigen2_Transform3d into a tf Transform. | |
| void | tf::TransformTFToEigen (const tf::Transform &t, Eigen::eigen2_Transform3d &k) |
| Converts a tf eigen2_Transform into an Eigen Transform3d. | |
| void | tf::VectorEigenToTF (const Eigen::Vector3d &k, tf::Vector3 &t) |
| Converts an Eigen Vector3d into a tf Vector3. | |
| void | tf::VectorTFToEigen (const tf::Vector3 &t, Eigen::Vector3d &k) |
| Converts a tf Vector3 into an Eigen Vector3d. | |