17 #ifndef CARTOGRAPHER_ROS_MSG_CONVERSION_H_ 18 #define CARTOGRAPHER_ROS_MSG_CONVERSION_H_ 21 #include "cartographer/kalman_filter/pose_tracker.h" 24 #include "geometry_msgs/Pose.h" 25 #include "geometry_msgs/Transform.h" 26 #include "geometry_msgs/TransformStamped.h" 27 #include "pcl/point_cloud.h" 28 #include "pcl/point_types.h" 30 #include "sensor_msgs/Imu.h" 31 #include "sensor_msgs/LaserScan.h" 32 #include "sensor_msgs/MultiEchoLaserScan.h" 33 #include "sensor_msgs/PointCloud2.h" 38 int64 timestamp,
const string& frame_id,
39 const ::cartographer::sensor::PointCloud& point_cloud);
42 const ::cartographer::transform::Rigid3d& rigid3d);
45 const ::cartographer::transform::Rigid3d& rigid3d);
50 const sensor_msgs::LaserScan& msg);
53 const sensor_msgs::MultiEchoLaserScan& msg);
56 const sensor_msgs::PointCloud2& message);
59 const geometry_msgs::TransformStamped& transform);
63 Eigen::Vector3d
ToEigen(
const geometry_msgs::Vector3& vector3);
65 Eigen::Quaterniond
ToEigen(
const geometry_msgs::Quaternion& quaternion);
68 const boost::array<double, 36>& covariance);
72 #endif // CARTOGRAPHER_ROS_MSG_CONVERSION_H_ PoseCovariance ToPoseCovariance(const boost::array< double, 36 > &covariance)
geometry_msgs::Pose ToGeometryMsgPose(const Rigid3d &rigid3d)
geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d &vector3d)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
PointCloudWithIntensities ToPointCloudWithIntensities(const sensor_msgs::LaserScan &msg)
geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d &rigid3d)
Eigen::Vector3d ToEigen(const geometry_msgs::Vector3 &vector3)
sensor_msgs::PointCloud2 ToPointCloud2Message(const int64 timestamp, const string &frame_id, const ::cartographer::sensor::PointCloud &point_cloud)