17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H 26 #include "cartographer_ros_msgs/LandmarkList.h" 27 #include "geometry_msgs/Pose.h" 28 #include "geometry_msgs/Transform.h" 29 #include "geometry_msgs/TransformStamped.h" 30 #include "nav_msgs/OccupancyGrid.h" 31 #include "pcl/point_cloud.h" 32 #include "pcl/point_types.h" 34 #include "sensor_msgs/Imu.h" 35 #include "sensor_msgs/LaserScan.h" 36 #include "sensor_msgs/MultiEchoLaserScan.h" 37 #include "sensor_msgs/PointCloud2.h" 42 int64_t timestamp,
const std::string& frame_id,
43 const ::cartographer::sensor::TimedPointCloud& point_cloud);
46 const ::cartographer::transform::Rigid3d& rigid3d);
49 const ::cartographer::transform::Rigid3d& rigid3d);
60 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
64 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
69 const cartographer_ros_msgs::LandmarkList& landmark_list);
72 const geometry_msgs::TransformStamped& transform);
76 Eigen::Vector3d
ToEigen(
const geometry_msgs::Vector3& vector3);
78 Eigen::Quaterniond
ToEigen(
const geometry_msgs::Quaternion& quaternion);
93 const double resolution,
const std::string& frame_id,
98 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H
sensor_msgs::PointCloud2 ToPointCloud2Message(const int64_t timestamp, const std::string &frame_id, const ::cartographer::sensor::TimedPointCloud &point_cloud)
std::unique_ptr< nav_msgs::OccupancyGrid > CreateOccupancyGridMsg(const cartographer::io::PaintSubmapSlicesResult &painted_slices, const double resolution, const std::string &frame_id, const ros::Time &time)
geometry_msgs::Pose ToGeometryMsgPose(const Rigid3d &rigid3d)
geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d &vector3d)
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
geometry_msgs::Transform ToGeometryMsgTransform(const Rigid3d &rigid3d)
UniversalTimeScaleClock::time_point Time
Eigen::Vector3d ToEigen(const geometry_msgs::Vector3 &vector3)
LandmarkData ToLandmarkData(const LandmarkList &landmark_list)
cartographer::transform::Rigid3d ComputeLocalFrameFromLatLong(const double latitude, const double longitude)
Eigen::Vector3d LatLongAltToEcef(const double latitude, const double longitude, const double altitude)
std::tuple<::cartographer::sensor::PointCloudWithIntensities, ::cartographer::common::Time > ToPointCloudWithIntensities(const sensor_msgs::LaserScan &msg)