33#ifndef DART_DYNAMICS_VOXELGRIDSHAPE_HPP_
34#define DART_DYNAMICS_VOXELGRIDSHAPE_HPP_
36#include "dart/config.hpp"
40 #include <octomap/octomap.h>
50class VoxelGridShape :
public Shape
55 explicit VoxelGridShape(
double resolution = 0.01);
62 ~VoxelGridShape()
override =
default;
65 const std::string& getType()
const override;
68 static const std::string& getStaticType();
86 void updateOccupancy(
const Eigen::Vector3d& point,
bool occupied =
true);
99 void updateOccupancy(
const Eigen::Vector3d& from,
const Eigen::Vector3d& to);
116 void updateOccupancy(
117 const octomap::Pointcloud& pointCloud,
118 const Eigen::Vector3d& sensorOrigin = Eigen::Vector3d::Zero(),
119 const Frame* relativeTo = Frame::World());
136 void updateOccupancy(
137 const octomap::Pointcloud& pointCloud,
138 const Eigen::Vector3d& sensorOrigin,
139 const Eigen::Isometry3d& relativeTo);
142 double getOccupancy(
const Eigen::Vector3d& point)
const;
145 Eigen::Matrix3d computeInertia(
double mass)
const override;
148 void notifyColorUpdated(
const Eigen::Vector4d& color)
override;
152 void updateBoundingBox()
const override;
155 void updateVolume()
const override;
boost::shared_ptr< T > fcl_shared_ptr
Definition BackwardCompatibility.hpp:106
Definition BulletCollisionDetector.cpp:60