$search

conversions.h File Reference

#include <octomap/octomap.h>
#include <octomap_ros/OctomapBinary.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <geometry_msgs/Point.h>
#include <tf/transform_datatypes.h>
Include dependency graph for conversions.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  octomap

Functions

template<class OctomapT >
static void octomap::octomapMapToMsg (const OctomapT &octomap, octomap_ros::OctomapBinary &mapMsg)
 Converts an octomap map structure to a ROS octomap msg as binary data. This will fill the timestamp of the header with the current time, but will not fill in the frame_id.
template<class OctomapT >
static void octomap::octomapMapToMsgData (const OctomapT &octomap, std::vector< int8_t > &mapData)
 Converts an octomap map structure to a ROS binary data, which can be put into a dedicated octomap msg.
template<class OctomapT >
static void octomap::octomapMsgDataToMap (const std::vector< int8_t > &mapData, OctomapT &octomap)
 Converts ROS binary data to an octomap map structure, e.g. coming from an octomap msg.
template<class OctomapT >
static void octomap::octomapMsgToMap (const octomap_ros::OctomapBinary &mapMsg, OctomapT &octomap)
 Converts a ROS octomap msg (binary data) to an octomap map structure.
template<class PointT >
static void octomap::pointcloudPCLToOctomap (const pcl::PointCloud< PointT > &pclCloud, Pointcloud &octomapCloud)
 Conversion from a PCL pointcloud to octomap::Pointcloud, used internally in OctoMap.
static octomap::point3d octomap::pointMsgToOctomap (const geometry_msgs::Point &ptMsg)
 Conversion from geometry_msgs::Point to octomap::point3d.
static geometry_msgs::Point octomap::pointOctomapToMsg (const point3d &octomapPt)
 Conversion from octomap::point3d to geometry_msgs::Point.
template<class PointT >
static PointT octomap::pointOctomapToPCL (const point3d &octomapPt)
static tf::Point octomap::pointOctomapToTf (const point3d &octomapPt)
 Conversion from octomap::point3d to tf::Point.
template<class PointT >
static octomap::point3d octomap::pointPCLToOctomap (const PointT &p)
 Conversion from pcl::PointT to octomap::point3d.
template<class PointT >
static void octomap::pointsOctomapToPCL (const point3d_list &points, pcl::PointCloud< PointT > &cloud)
 Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to pcl PointCloud.
static octomap::point3d octomap::pointTfToOctomap (const tf::Point &ptTf)
 Conversion from tf::Point to octomap::point3d.
static tf::Pose octomap::poseOctomapToTf (const octomap::pose6d &octomapPose)
 Conversion from octomap::pose6f to tf::Pose.
static octomap::pose6d octomap::poseTfToOctomap (const tf::Pose &poseTf)
 Conversion from tf::Pose to octomap::pose6d.
static tf::Quaternion octomap::quaternionOctomapToTf (const octomath::Quaternion &octomapQ)
 Conversion from octomap Quaternion to tf::Quaternion.
static octomath::Quaternion octomap::quaternionTfToOctomap (const tf::Quaternion &qTf)
 Conversion from tf::Quaternion to octomap Quaternion.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


octomap_ros
Author(s): Armin Hornung
autogenerated on Tue Mar 5 12:07:19 2013