1 #ifndef AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_
2 #define AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_
4 #ifdef DART_HAS_VOXELGRIDSHAPE
9 #include <dart/dynamics/dynamics.hpp>
13 namespace perception {
16 class VoxelGridPerceptionModule
24 VoxelGridPerceptionModule(
25 const ros::NodeHandle& nodeHandle,
26 const std::string& pointCloudTopic,
27 std::shared_ptr<dart::dynamics::VoxelGridShape> voxelGridShape =
nullptr);
30 virtual ~VoxelGridPerceptionModule() =
default;
33 std::shared_ptr<dart::dynamics::VoxelGridShape> getVoxelGridShape();
36 std::shared_ptr<const dart::dynamics::VoxelGridShape> getVoxelGridShape()
48 const Eigen::Vector3d& sensorOrigin,
49 const Eigen::Isometry3d& inCoordinatesOf,
50 const ros::Duration& timeout);
61 const Eigen::Vector3d& sensorOrigin,
62 const dart::dynamics::Frame& inCoordinatesOf,
63 const ros::Duration& timeout);
67 ros::NodeHandle mNodeHandle;
70 std::string mPointCloudTopic;
73 std::shared_ptr<dart::dynamics::VoxelGridShape> mVoxelGridShape;
76 octomap::Pointcloud mOctomapPointCloud;
82 #endif // DART_HAS_VOXELGRIDSHAPE
84 #endif // AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_