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_MSG_CONVERSION_H_
18 #define CARTOGRAPHER_ROS_MSG_CONVERSION_H_
19 
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"
34 
35 namespace cartographer_ros {
36 
37 sensor_msgs::PointCloud2 ToPointCloud2Message(
38  int64 timestamp, const string& frame_id,
39  const ::cartographer::sensor::PointCloud& point_cloud);
40 
41 geometry_msgs::Transform ToGeometryMsgTransform(
42  const ::cartographer::transform::Rigid3d& rigid3d);
43 
44 geometry_msgs::Pose ToGeometryMsgPose(
45  const ::cartographer::transform::Rigid3d& rigid3d);
46 
47 geometry_msgs::Point ToGeometryMsgPoint(const Eigen::Vector3d& vector3d);
48 
50  const sensor_msgs::LaserScan& msg);
51 
53  const sensor_msgs::MultiEchoLaserScan& msg);
54 
56  const sensor_msgs::PointCloud2& message);
57 
59  const geometry_msgs::TransformStamped& transform);
60 
61 ::cartographer::transform::Rigid3d ToRigid3d(const geometry_msgs::Pose& pose);
62 
63 Eigen::Vector3d ToEigen(const geometry_msgs::Vector3& vector3);
64 
65 Eigen::Quaterniond ToEigen(const geometry_msgs::Quaternion& quaternion);
66 
67 ::cartographer::kalman_filter::PoseCovariance ToPoseCovariance(
68  const boost::array<double, 36>& covariance);
69 
70 } // namespace cartographer_ros
71 
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)
int64_t int64
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)


cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40