conversions.h
Go to the documentation of this file.
1 
9 /*
10  * Copyright (c) 2011, A. Hornung, University of Freiburg
11  * All rights reserved.
12  *
13  * Redistribution and use in source and binary forms, with or without
14  * modification, are permitted provided that the following conditions are met:
15  *
16  * * Redistributions of source code must retain the above copyright
17  * notice, this list of conditions and the following disclaimer.
18  * * Redistributions in binary form must reproduce the above copyright
19  * notice, this list of conditions and the following disclaimer in the
20  * documentation and/or other materials provided with the distribution.
21  * * Neither the name of the University of Freiburg nor the names of its
22  * contributors may be used to endorse or promote products derived from
23  * this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
26  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
27  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
28  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
29  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
30  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
31  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
32  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
33  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
34  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  */
37 
38 #ifndef OCTOMAP_ROS_CONVERSIONS_H
39 #define OCTOMAP_ROS_CONVERSIONS_H
40 
41 #include <octomap/octomap.h>
42 
43 #include <sensor_msgs/PointCloud2.h>
44 #include <geometry_msgs/Point.h>
45 #include <tf/transform_datatypes.h>
46 
47 namespace octomap {
55  void pointsOctomapToPointCloud2(const point3d_list& points, sensor_msgs::PointCloud2& cloud);
56 
63  void pointCloud2ToOctomap(const sensor_msgs::PointCloud2& cloud, Pointcloud& octomapCloud);
64 
66  static inline geometry_msgs::Point pointOctomapToMsg(const point3d& octomapPt){
67  geometry_msgs::Point pt;
68  pt.x = octomapPt.x();
69  pt.y = octomapPt.y();
70  pt.z = octomapPt.z();
71 
72  return pt;
73  }
74 
76  static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::Point& ptMsg){
77  return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z);
78  }
79 
81  static inline tf::Point pointOctomapToTf(const point3d& octomapPt){
82  return tf::Point(octomapPt.x(), octomapPt.y(), octomapPt.z());
83  }
84 
86  static inline octomap::point3d pointTfToOctomap(const tf::Point& ptTf){
87  return point3d(ptTf.x(), ptTf.y(), ptTf.z());
88  }
89 
92  return tf::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u());
93  }
94 
97  return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
98  }
99 
101  static inline tf::Pose poseOctomapToTf(const octomap::pose6d& octomapPose){
102  return tf::Pose(quaternionOctomapToTf(octomapPose.rot()), pointOctomapToTf(octomapPose.trans()));
103  }
104 
106  static inline octomap::pose6d poseTfToOctomap(const tf::Pose& poseTf){
108  }
109 }
110 
111 #endif
tf::Transform::getRotation
Quaternion getRotation() const
octomap::pointsOctomapToPointCloud2
void pointsOctomapToPointCloud2(const point3d_list &points, sensor_msgs::PointCloud2 &cloud)
Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to sensor_msgs::Po...
Definition: conversions.cpp:52
octomath::Quaternion::x
float & x()
octomap::pointTfToOctomap
static octomap::point3d pointTfToOctomap(const tf::Point &ptTf)
Conversion from tf::Point to octomap::point3d.
Definition: conversions.h:86
octomap::pointCloud2ToOctomap
void pointCloud2ToOctomap(const sensor_msgs::PointCloud2 &cloud, Pointcloud &octomapCloud)
Conversion from a sensor_msgs::PointCLoud2 to octomap::Pointcloud, used internally in OctoMap.
Definition: conversions.cpp:92
tf::Pose
tf::Transform Pose
octomap::pointOctomapToTf
static tf::Point pointOctomapToTf(const point3d &octomapPt)
Conversion from octomap::point3d to tf::Point.
Definition: conversions.h:81
octomath::Vector3
tf::Point
tf::Vector3 Point
octomap::pointMsgToOctomap
static octomap::point3d pointMsgToOctomap(const geometry_msgs::Point &ptMsg)
Conversion from geometry_msgs::Point to octomap::point3d.
Definition: conversions.h:76
octomath::Quaternion::y
float & y()
tf::Transform
octomap::pointOctomapToMsg
static geometry_msgs::Point pointOctomapToMsg(const point3d &octomapPt)
Conversion from octomap::point3d to geometry_msgs::Point.
Definition: conversions.h:66
point3d_list
std::list< octomath::Vector3 > point3d_list
octomap::poseTfToOctomap
static octomap::pose6d poseTfToOctomap(const tf::Pose &poseTf)
Conversion from tf::Pose to octomap::pose6d.
Definition: conversions.h:106
octomath::Quaternion::u
float & u()
transform_datatypes.h
octomath::Vector3::y
float & y()
octomath::Pose6D::rot
Quaternion & rot()
octomap.h
octomap::quaternionOctomapToTf
static tf::Quaternion quaternionOctomapToTf(const octomath::Quaternion &octomapQ)
Conversion from octomap Quaternion to tf::Quaternion.
Definition: conversions.h:91
octomap
octomath::Pose6D
octomap::quaternionTfToOctomap
static octomath::Quaternion quaternionTfToOctomap(const tf::Quaternion &qTf)
Conversion from tf::Quaternion to octomap Quaternion.
Definition: conversions.h:96
octomath::Quaternion::z
float & z()
octomap::poseOctomapToTf
static tf::Pose poseOctomapToTf(const octomap::pose6d &octomapPose)
Conversion from octomap::pose6f to tf::Pose.
Definition: conversions.h:101
octomath::Vector3::z
float & z()
octomap::point3d
octomath::Vector3 point3d
octomath::Vector3::x
float & x()
tf::Quaternion
octomath::Quaternion
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
octomap::pose6d
octomath::Pose6D pose6d
octomath::Pose6D::trans
Vector3 & trans()


octomap_ros
Author(s): Armin Hornung
autogenerated on Fri Mar 24 2023 02:43:30