32 #ifndef TF2_SENSOR_MSGS_H 33 #define TF2_SENSOR_MSGS_H 36 #include <sensor_msgs/PointCloud2.h> 37 #include <sensor_msgs/Imu.h> 38 #include <sensor_msgs/MagneticField.h> 40 #include <Eigen/Eigen> 41 #include <Eigen/Geometry> 62 const std::string&
getFrameId(
const sensor_msgs::Imu &p) {
return p.header.frame_id;}
69 void transformCovariance(
const boost::array<double, 9>& in, boost::array<double, 9>& out, Eigen::Quaternion<double> r){
71 Eigen::Map<const Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > cov_in(in.data());
72 Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor> > cov_out(out.data());
73 cov_out = r * cov_in * r.inverse();
82 void doTransform(
const sensor_msgs::Imu &imu_in, sensor_msgs::Imu &imu_out,
const geometry_msgs::TransformStamped& t_in)
85 imu_out.header = t_in.header;
88 Eigen::Quaternion<double> r(
89 t_in.transform.rotation.w, t_in.transform.rotation.x, t_in.transform.rotation.y, t_in.transform.rotation.z);
90 Eigen::Transform<double,3,Eigen::Affine> t(r);
92 Eigen::Vector3d vel = t * Eigen::Vector3d(
93 imu_in.angular_velocity.x, imu_in.angular_velocity.y, imu_in.angular_velocity.z);
95 imu_out.angular_velocity.x = vel.x();
96 imu_out.angular_velocity.y = vel.y();
97 imu_out.angular_velocity.z = vel.z();
99 transformCovariance(imu_in.angular_velocity_covariance, imu_out.angular_velocity_covariance, r);
101 Eigen::Vector3d accel = t * Eigen::Vector3d(
102 imu_in.linear_acceleration.x, imu_in.linear_acceleration.y, imu_in.linear_acceleration.z);
105 imu_out.linear_acceleration.x = accel.x();
106 imu_out.linear_acceleration.y = accel.y();
107 imu_out.linear_acceleration.z = accel.z();
109 transformCovariance(imu_in.linear_acceleration_covariance, imu_out.linear_acceleration_covariance, r);
111 Eigen::Quaternion<double> orientation = r * Eigen::Quaternion<double>(
112 imu_in.orientation.w, imu_in.orientation.x, imu_in.orientation.y, imu_in.orientation.z) * r.inverse();
114 imu_out.orientation.w = orientation.w();
115 imu_out.orientation.x = orientation.x();
116 imu_out.orientation.y = orientation.y();
117 imu_out.orientation.z = orientation.z();
124 sensor_msgs::Imu
toMsg(
const sensor_msgs::Imu &in)
130 void fromMsg(
const sensor_msgs::Imu &msg, sensor_msgs::Imu &out)
151 const std::string&
getFrameId(
const sensor_msgs::MagneticField &p) {
return p.header.frame_id;}
158 void doTransform(
const sensor_msgs::MagneticField &mag_in, sensor_msgs::MagneticField &mag_out,
const geometry_msgs::TransformStamped& t_in)
161 mag_out.header = t_in.header;
164 Eigen::Quaternion<double> r(
165 t_in.transform.rotation.w, t_in.transform.rotation.x, t_in.transform.rotation.y, t_in.transform.rotation.z);
166 Eigen::Transform<double,3,Eigen::Affine> t(r);
168 Eigen::Vector3d mag = t * Eigen::Vector3d(
169 mag_in.magnetic_field.x, mag_in.magnetic_field.y, mag_in.magnetic_field.z);
171 mag_out.magnetic_field.x = mag.x();
172 mag_out.magnetic_field.y = mag.y();
173 mag_out.magnetic_field.z = mag.z();
175 transformCovariance(mag_in.magnetic_field_covariance, mag_out.magnetic_field_covariance, r);
180 sensor_msgs::MagneticField
toMsg(
const sensor_msgs::MagneticField &in)
186 void fromMsg(
const sensor_msgs::MagneticField &msg, sensor_msgs::MagneticField &out)
193 #endif // TF2_SENSOR_MSGS_IMU_H const std::string & getFrameId(const T &t)
void transformCovariance(const boost::array< double, 9 > &in, boost::array< double, 9 > &out, Eigen::Quaternion< double > r)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
void fromMsg(const A &, B &b)
const ros::Time & getTimestamp(const T &t)