msg_conversion.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MSG_CONVERSION_H
19 
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"
38 
39 namespace cartographer_ros {
40 
41 sensor_msgs::PointCloud2 ToPointCloud2Message(
42  int64_t timestamp, const std::string& frame_id,
43  const ::cartographer::sensor::TimedPointCloud& point_cloud);
44 
45 geometry_msgs::Transform ToGeometryMsgTransform(
46  const ::cartographer::transform::Rigid3d& rigid3d);
47 
48 geometry_msgs::Pose ToGeometryMsgPose(
49  const ::cartographer::transform::Rigid3d& rigid3d);
50 
51 geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d& vector3d);
52 
53 // Converts ROS message to point cloud. Returns the time when the last point
54 // was acquired (different from the ROS timestamp). Timing of points is given in
55 // the fourth component of each point relative to `Time`.
58 ToPointCloudWithIntensities(const sensor_msgs::LaserScan& msg);
59 
60 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
62 ToPointCloudWithIntensities(const sensor_msgs::MultiEchoLaserScan& msg);
63 
64 std::tuple<::cartographer::sensor::PointCloudWithIntensities,
66 ToPointCloudWithIntensities(const sensor_msgs::PointCloud2& message);
67 
69  const cartographer_ros_msgs::LandmarkList& landmark_list);
70 
72  const geometry_msgs::TransformStamped& transform);
73 
74 ::cartographer::transform::Rigid3d ToRigid3d(const geometry_msgs::Pose& pose);
75 
76 Eigen::Vector3d ToEigen(const geometry_msgs::Vector3& vector3);
77 
78 Eigen::Quaterniond ToEigen(const geometry_msgs::Quaternion& quaternion);
79 
80 // Converts from WGS84 (latitude, longitude, altitude) to ECEF.
81 Eigen::Vector3d LatLongAltToEcef(double latitude, double longitude,
82  double altitude);
83 
84 // Returns a transform that takes ECEF coordinates from nearby points to a local
85 // frame that has z pointing upwards.
87  double longitude);
88 
89 // Points to an occupancy grid message at a specific resolution from painted
90 // submap slices obtained via ::cartographer::io::PaintSubmapSlices(...).
91 std::unique_ptr<nav_msgs::OccupancyGrid> CreateOccupancyGridMsg(
92  const cartographer::io::PaintSubmapSlicesResult& painted_slices,
93  const double resolution, const std::string& frame_id,
94  const ros::Time& time);
95 
96 } // namespace cartographer_ros
97 
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)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05