29 #ifndef POSE_INFO_CONTAINER_H__ 30 #define POSE_INFO_CONTAINER_H__ 33 #include <geometry_msgs/PoseStamped.h> 34 #include <geometry_msgs/PoseWithCovarianceStamped.h> 41 void update(
const Eigen::Vector3f& slamPose,
const Eigen::Matrix3f& slamCov,
const ros::Time& stamp,
const std::string& frame_id);
49 geometry_msgs::PoseWithCovarianceStamped
covPose_;
const geometry_msgs::PoseStamped & getPoseStamped()
tf::Transform poseTransform_
const geometry_msgs::PoseWithCovarianceStamped & getPoseWithCovarianceStamped()
void update(const Eigen::Vector3f &slamPose, const Eigen::Matrix3f &slamCov, const ros::Time &stamp, const std::string &frame_id)
geometry_msgs::PoseWithCovarianceStamped covPose_
const tf::Transform & getTfTransform()
geometry_msgs::PoseStamped stampedPose_