|
| 1 | +/** |
| 2 | + * OctoMap ROS integration |
| 3 | + * |
| 4 | + * @author A. Hornung, University of Freiburg, Copyright (C) 2011-2012. |
| 5 | + * @see http://www.ros.org/wiki/octomap_ros |
| 6 | + * License: BSD |
| 7 | + */ |
| 8 | + |
| 9 | +// Copyright 2011, A. Hornung, University of Freiburg. All rights reserved. |
| 10 | +// |
| 11 | +// Redistribution and use in source and binary forms, with or without |
| 12 | +// modification, are permitted provided that the following conditions are met: |
| 13 | +// |
| 14 | +// * Redistributions of source code must retain the above copyright |
| 15 | +// notice, this list of conditions and the following disclaimer. |
| 16 | +// |
| 17 | +// * Redistributions in binary form must reproduce the above copyright |
| 18 | +// notice, this list of conditions and the following disclaimer in the |
| 19 | +// documentation and/or other materials provided with the distribution. |
| 20 | +// |
| 21 | +// * Neither the name of the Willow Garage 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 HOLDER 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 | +#ifndef OCTOMAP_ROS__CONVERSIONS_HPP_ |
| 38 | +#define OCTOMAP_ROS__CONVERSIONS_HPP_ |
| 39 | + |
| 40 | +#include <octomap/octomap.h> |
| 41 | + |
| 42 | +#include <geometry_msgs/msg/point.hpp> |
| 43 | +#include <sensor_msgs/msg/point_cloud2.hpp> |
| 44 | +#include <tf2/LinearMath/Quaternion.h> |
| 45 | +#include <tf2/LinearMath/Transform.h> |
| 46 | +#include <tf2/LinearMath/Vector3.h> |
| 47 | + |
| 48 | +namespace octomap |
| 49 | +{ |
| 50 | +/** |
| 51 | + * @brief Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to |
| 52 | + * sensor_msgs::PointCloud2 |
| 53 | + * |
| 54 | + * @param points |
| 55 | + * @param cloud |
| 56 | + */ |
| 57 | +void pointsOctomapToPointCloud2( |
| 58 | + const octomap::point3d_list & points, |
| 59 | + sensor_msgs::msg::PointCloud2 & cloud); |
| 60 | + |
| 61 | +/** |
| 62 | + * @brief Conversion from a sensor_msgs::PointCLoud2 |
| 63 | + * to octomap::Pointcloud, used internally in OctoMap |
| 64 | + * |
| 65 | + * @param cloud |
| 66 | + * @param octomapCloud |
| 67 | + */ |
| 68 | +void pointCloud2ToOctomap( |
| 69 | + const sensor_msgs::msg::PointCloud2 & cloud, |
| 70 | + octomap::Pointcloud & octomapCloud); |
| 71 | + |
| 72 | +/// Conversion from octomap::point3d to geometry_msgs::Point |
| 73 | +static inline geometry_msgs::msg::Point pointOctomapToMsg(const octomap::point3d & octomapPt) |
| 74 | +{ |
| 75 | + return geometry_msgs::build<geometry_msgs::msg::Point>() |
| 76 | + .x(octomapPt.x()) |
| 77 | + .y(octomapPt.y()) |
| 78 | + .z(octomapPt.z()); |
| 79 | +} |
| 80 | + |
| 81 | +/// Conversion from geometry_msgs::Point to octomap::point3d |
| 82 | +static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::msg::Point & ptMsg) |
| 83 | +{ |
| 84 | + return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z); |
| 85 | +} |
| 86 | + |
| 87 | +/// Conversion from octomap::point3d to tf2::Vector3 |
| 88 | +static inline tf2::Vector3 pointOctomapToTf(const point3d & octomapPt) |
| 89 | +{ |
| 90 | + return tf2::Vector3(octomapPt.x(), octomapPt.y(), octomapPt.z()); |
| 91 | +} |
| 92 | + |
| 93 | +/// Conversion from tf::Point to octomap::point3d |
| 94 | +static inline octomap::point3d pointTfToOctomap(const tf2::Vector3 & vTf) |
| 95 | +{ |
| 96 | + return point3d(vTf.x(), vTf.y(), vTf.z()); |
| 97 | +} |
| 98 | + |
| 99 | +/// Conversion from octomap Quaternion to tf2::Quaternion |
| 100 | +static inline tf2::Quaternion quaternionOctomapToTf(const octomath::Quaternion & octomapQ) |
| 101 | +{ |
| 102 | + return tf2::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u()); |
| 103 | +} |
| 104 | + |
| 105 | +/// Conversion from tf2::Quaternion to octomap Quaternion |
| 106 | +static inline octomath::Quaternion quaternionTfToOctomap(const tf2::Quaternion & qTf) |
| 107 | +{ |
| 108 | + return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z()); |
| 109 | +} |
| 110 | + |
| 111 | +/// Conversion from octomap::pose6f to tf::Pose |
| 112 | +static inline tf2::Transform poseOctomapToTf(const octomap::pose6d & octomapPose) |
| 113 | +{ |
| 114 | + return tf2::Transform( |
| 115 | + quaternionOctomapToTf(octomapPose.rot()), |
| 116 | + pointOctomapToTf(octomapPose.trans())); |
| 117 | +} |
| 118 | + |
| 119 | +/// Conversion from tf::Pose to octomap::pose6d |
| 120 | +static inline octomap::pose6d poseTfToOctomap(const tf2::Transform & transformTf) |
| 121 | +{ |
| 122 | + return octomap::pose6d( |
| 123 | + pointTfToOctomap(transformTf.getOrigin()), |
| 124 | + quaternionTfToOctomap(transformTf.getRotation())); |
| 125 | +} |
| 126 | + |
| 127 | + |
| 128 | +} // namespace octomap |
| 129 | + |
| 130 | + |
| 131 | +#endif // OCTOMAP_ROS__CONVERSIONS_HPP_ |
0 commit comments