observation.h 2.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #ifndef COSTMAP_2D_OBSERVATION_H_
  2. #define COSTMAP_2D_OBSERVATION_H_
  3. #include <geometry_msgs/Point.h>
  4. #include <sensor_msgs/PointCloud2.h>
  5. namespace costmap_2d
  6. {
  7. /**
  8. * @brief Stores an observation in terms of a point cloud and the origin of the source
  9. * @note Tried to make members and constructor arguments const but the compiler would not accept the default
  10. * assignment operator for vector insertion!
  11. */
  12. class Observation
  13. {
  14. public:
  15. /**
  16. * @brief Creates an empty observation
  17. */
  18. Observation() :
  19. cloud_(new sensor_msgs::PointCloud2()), obstacle_range_(0.0), raytrace_range_(0.0)
  20. {
  21. }
  22. virtual ~Observation()
  23. {
  24. delete cloud_;
  25. }
  26. /**
  27. * @brief Creates an observation from an origin point and a point cloud
  28. * @param origin The origin point of the observation
  29. * @param cloud The point cloud of the observation
  30. * @param obstacle_range The range out to which an observation should be able to insert obstacles
  31. * @param raytrace_range The range out to which an observation should be able to clear via raytracing
  32. */
  33. Observation(geometry_msgs::Point& origin, const sensor_msgs::PointCloud2 &cloud,
  34. double obstacle_range, double raytrace_range) :
  35. origin_(origin), cloud_(new sensor_msgs::PointCloud2(cloud)),
  36. obstacle_range_(obstacle_range), raytrace_range_(raytrace_range)
  37. {
  38. }
  39. /**
  40. * @brief Copy constructor
  41. * @param obs The observation to copy
  42. */
  43. Observation(const Observation& obs) :
  44. origin_(obs.origin_), cloud_(new sensor_msgs::PointCloud2(*(obs.cloud_))),
  45. obstacle_range_(obs.obstacle_range_), raytrace_range_(obs.raytrace_range_)
  46. {
  47. }
  48. /**
  49. * @brief Creates an observation from a point cloud
  50. * @param cloud The point cloud of the observation
  51. * @param obstacle_range The range out to which an observation should be able to insert obstacles
  52. */
  53. Observation(const sensor_msgs::PointCloud2 &cloud, double obstacle_range) :
  54. cloud_(new sensor_msgs::PointCloud2(cloud)), obstacle_range_(obstacle_range), raytrace_range_(0.0)
  55. {
  56. }
  57. geometry_msgs::Point origin_;
  58. sensor_msgs::PointCloud2* cloud_;
  59. double obstacle_range_, raytrace_range_;
  60. double min_obstacle_height_, max_obstacle_height_;
  61. };
  62. } // namespace costmap_2d
  63. #endif // COSTMAP_2D_OBSERVATION_H_