Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H
00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H
00019
00020 #include "cartographer/common/time.h"
00021 #include "cartographer/io/submap_painter.h"
00022 #include "cartographer/sensor/landmark_data.h"
00023 #include "cartographer/sensor/point_cloud.h"
00024 #include "cartographer/transform/rigid_transform.h"
00025 #include "cartographer_ros_msgs/LandmarkList.h"
00026 #include "geometry_msgs/Pose.h"
00027 #include "geometry_msgs/Transform.h"
00028 #include "geometry_msgs/TransformStamped.h"
00029 #include "nav_msgs/OccupancyGrid.h"
00030 #include "sensor_msgs/Imu.h"
00031 #include "sensor_msgs/LaserScan.h"
00032 #include "sensor_msgs/MultiEchoLaserScan.h"
00033 #include "sensor_msgs/PointCloud2.h"
00034
00035 namespace cartographer_ros {
00036
00037 sensor_msgs::PointCloud2 ToPointCloud2Message(
00038 int64_t timestamp, const std::string& frame_id,
00039 const ::cartographer::sensor::TimedPointCloud& point_cloud);
00040
00041 geometry_msgs::Transform ToGeometryMsgTransform(
00042 const ::cartographer::transform::Rigid3d& rigid3d);
00043
00044 geometry_msgs::Pose ToGeometryMsgPose(
00045 const ::cartographer::transform::Rigid3d& rigid3d);
00046
00047 geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d& vector3d);
00048
00049
00050
00051
00052 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
00053 ::cartographer::common::Time>
00054 ToPointCloudWithIntensities(const sensor_msgs::LaserScan& msg);
00055
00056 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
00057 ::cartographer::common::Time>
00058 ToPointCloudWithIntensities(const sensor_msgs::MultiEchoLaserScan& msg);
00059
00060 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
00061 ::cartographer::common::Time>
00062 ToPointCloudWithIntensities(const sensor_msgs::PointCloud2& msg);
00063
00064 ::cartographer::sensor::LandmarkData ToLandmarkData(
00065 const cartographer_ros_msgs::LandmarkList& landmark_list);
00066
00067 ::cartographer::transform::Rigid3d ToRigid3d(
00068 const geometry_msgs::TransformStamped& transform);
00069
00070 ::cartographer::transform::Rigid3d ToRigid3d(const geometry_msgs::Pose& pose);
00071
00072 Eigen::Vector3d ToEigen(const geometry_msgs::Vector3& vector3);
00073
00074 Eigen::Quaterniond ToEigen(const geometry_msgs::Quaternion& quaternion);
00075
00076
00077 Eigen::Vector3d LatLongAltToEcef(double latitude, double longitude,
00078 double altitude);
00079
00080
00081
00082 cartographer::transform::Rigid3d ComputeLocalFrameFromLatLong(double latitude,
00083 double longitude);
00084
00085
00086
00087 std::unique_ptr<nav_msgs::OccupancyGrid> CreateOccupancyGridMsg(
00088 const cartographer::io::PaintSubmapSlicesResult& painted_slices,
00089 const double resolution, const std::string& frame_id,
00090 const ros::Time& time);
00091
00092 }
00093
00094 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H