Aikido
VoxelGridModule.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_
2 #define AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_
3 
4 #ifdef DART_HAS_VOXELGRIDSHAPE
5 
6 #include <memory>
7 #include <string>
8 
9 #include <dart/dynamics/dynamics.hpp>
10 #include <ros/ros.h>
11 
12 namespace aikido {
13 namespace perception {
14 
16 class VoxelGridPerceptionModule
17 {
18 public:
24  VoxelGridPerceptionModule(
25  const ros::NodeHandle& nodeHandle,
26  const std::string& pointCloudTopic,
27  std::shared_ptr<dart::dynamics::VoxelGridShape> voxelGridShape = nullptr);
28 
30  virtual ~VoxelGridPerceptionModule() = default;
31 
33  std::shared_ptr<dart::dynamics::VoxelGridShape> getVoxelGridShape();
34 
36  std::shared_ptr<const dart::dynamics::VoxelGridShape> getVoxelGridShape()
37  const;
38 
47  bool update(
48  const Eigen::Vector3d& sensorOrigin,
49  const Eigen::Isometry3d& inCoordinatesOf,
50  const ros::Duration& timeout);
51 
60  bool update(
61  const Eigen::Vector3d& sensorOrigin,
62  const dart::dynamics::Frame& inCoordinatesOf,
63  const ros::Duration& timeout);
64 
65 private:
67  ros::NodeHandle mNodeHandle;
68 
70  std::string mPointCloudTopic;
71 
73  std::shared_ptr<dart::dynamics::VoxelGridShape> mVoxelGridShape;
74 
76  octomap::Pointcloud mOctomapPointCloud;
77 };
78 
79 } // namespace perception
80 } // namespace aikido
81 
82 #endif // DART_HAS_VOXELGRIDSHAPE
83 
84 #endif // AIKIDO_PERCEPTION_VOXELGRIDMODULE_HPP_
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4