#include <tf2/convert.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/MagneticField.h>
#include <sensor_msgs/point_cloud2_iterator.h>
#include <Eigen/Eigen>
#include <Eigen/Geometry>
Go to the source code of this file.
Namespaces | |
namespace | tf2 |
Functions | |
template<> | |
void | tf2::doTransform (const sensor_msgs::Imu &imu_in, sensor_msgs::Imu &imu_out, const geometry_msgs::TransformStamped &t_in) |
template<> | |
void | tf2::doTransform (const sensor_msgs::MagneticField &mag_in, sensor_msgs::MagneticField &mag_out, const geometry_msgs::TransformStamped &t_in) |
void | tf2::fromMsg (const sensor_msgs::Imu &msg, sensor_msgs::Imu &out) |
void | tf2::fromMsg (const sensor_msgs::MagneticField &msg, sensor_msgs::MagneticField &out) |
template<> | |
const std::string & | tf2::getFrameId (const sensor_msgs::Imu &p) |
template<> | |
const std::string & | tf2::getFrameId (const sensor_msgs::MagneticField &p) |
template<> | |
const ros::Time & | tf2::getTimestamp (const sensor_msgs::Imu &p) |
template<> | |
const ros::Time & | tf2::getTimestamp (const sensor_msgs::MagneticField &p) |
sensor_msgs::Imu | tf2::toMsg (const sensor_msgs::Imu &in) |
sensor_msgs::MagneticField | tf2::toMsg (const sensor_msgs::MagneticField &in) |
void | tf2::transformCovariance (const boost::array< double, 9 > &in, boost::array< double, 9 > &out, Eigen::Quaternion< double > r) |