Namespaces | Functions
conversions.h File Reference
#include <octomap/octomap.h>
#include <sensor_msgs/PointCloud2.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

 octomap
 

Functions

void octomap::pointCloud2ToOctomap (const sensor_msgs::PointCloud2 &cloud, Pointcloud &octomapCloud)
 Conversion from a sensor_msgs::PointCLoud2 to octomap::Pointcloud, used internally in OctoMap. More...
 
static octomap::point3d octomap::pointMsgToOctomap (const geometry_msgs::Point &ptMsg)
 Conversion from geometry_msgs::Point to octomap::point3d. More...
 
static geometry_msgs::Point octomap::pointOctomapToMsg (const point3d &octomapPt)
 Conversion from octomap::point3d to geometry_msgs::Point. More...
 
static tf::Point octomap::pointOctomapToTf (const point3d &octomapPt)
 Conversion from octomap::point3d to tf::Point. More...
 
void octomap::pointsOctomapToPointCloud2 (const point3d_list &points, sensor_msgs::PointCloud2 &cloud)
 Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to sensor_msgs::PointCloud2. More...
 
static octomap::point3d octomap::pointTfToOctomap (const tf::Point &ptTf)
 Conversion from tf::Point to octomap::point3d. More...
 
static tf::Pose octomap::poseOctomapToTf (const octomap::pose6d &octomapPose)
 Conversion from octomap::pose6f to tf::Pose. More...
 
static octomap::pose6d octomap::poseTfToOctomap (const tf::Pose &poseTf)
 Conversion from tf::Pose to octomap::pose6d. More...
 
static tf::Quaternion octomap::quaternionOctomapToTf (const octomath::Quaternion &octomapQ)
 Conversion from octomap Quaternion to tf::Quaternion. More...
 
static octomath::Quaternion octomap::quaternionTfToOctomap (const tf::Quaternion &qTf)
 Conversion from tf::Quaternion to octomap Quaternion. More...
 


octomap_ros
Author(s): Armin Hornung
autogenerated on Mon Jun 10 2019 14:03:16