36 header.frame_id = frame_id;
39 pose.position.x = slamPose.x();
40 pose.position.y = slamPose.y();
42 pose.orientation.w =
cos(slamPose.z()*0.5f);
43 pose.orientation.z =
sin(slamPose.z()*0.5f);
50 boost::array<double, 36>& cov(
covPose_.pose.covariance);
52 cov[0] =
static_cast<double>(slamCov(0,0));
53 cov[7] =
static_cast<double>(slamCov(1,1));
54 cov[35] =
static_cast<double>(slamCov(2,2));
56 double xyC =
static_cast<double>(slamCov(0,1));
60 double xaC =
static_cast<double>(slamCov(0,2));
64 double yaC =
static_cast<double>(slamCov(1,2));
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
tf::Transform poseTransform_
void update(const Eigen::Vector3f &slamPose, const Eigen::Matrix3f &slamCov, const ros::Time &stamp, const std::string &frame_id)
geometry_msgs::PoseWithCovarianceStamped covPose_
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
geometry_msgs::PoseStamped stampedPose_