38 #ifndef OCTOMAP_ROS_CONVERSIONS_H 39 #define OCTOMAP_ROS_CONVERSIONS_H 43 #include <sensor_msgs/PointCloud2.h> 44 #include <geometry_msgs/Point.h> 67 geometry_msgs::Point pt;
82 return tf::Point(octomapPt.
x(), octomapPt.
y(), octomapPt.
z());
static octomap::point3d pointMsgToOctomap(const geometry_msgs::Point &ptMsg)
Conversion from geometry_msgs::Point to octomap::point3d.
void pointCloud2ToOctomap(const sensor_msgs::PointCloud2 &cloud, Pointcloud &octomapCloud)
Conversion from a sensor_msgs::PointCLoud2 to octomap::Pointcloud, used internally in OctoMap...
static tf::Point pointOctomapToTf(const point3d &octomapPt)
Conversion from octomap::point3d to tf::Point.
static octomap::point3d pointTfToOctomap(const tf::Point &ptTf)
Conversion from tf::Point to octomap::point3d.
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
static geometry_msgs::Point pointOctomapToMsg(const point3d &octomapPt)
Conversion from octomap::point3d to geometry_msgs::Point.
static octomap::pose6d poseTfToOctomap(const tf::Pose &poseTf)
Conversion from tf::Pose to octomap::pose6d.
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::list< octomath::Vector3 > point3d_list
static octomath::Quaternion quaternionTfToOctomap(const tf::Quaternion &qTf)
Conversion from tf::Quaternion to octomap Quaternion.
octomath::Vector3 point3d
static tf::Quaternion quaternionOctomapToTf(const octomath::Quaternion &octomapQ)
Conversion from octomap Quaternion to tf::Quaternion.
static tf::Pose poseOctomapToTf(const octomap::pose6d &octomapPose)
Conversion from octomap::pose6f to tf::Pose.
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...