Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
observation_buffer.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  *********************************************************************/
37 #ifndef NAV2_COSTMAP_2D__OBSERVATION_BUFFER_HPP_
38 #define NAV2_COSTMAP_2D__OBSERVATION_BUFFER_HPP_
39 
40 #include <vector>
41 #include <list>
42 #include <string>
43 
44 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
45 #include "rclcpp/time.hpp"
46 #include "tf2_ros/buffer.h"
47 #include "tf2_sensor_msgs/tf2_sensor_msgs.hpp"
48 #include "sensor_msgs/msg/point_cloud2.hpp"
49 #include "nav2_costmap_2d/observation.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
51 
52 
53 namespace nav2_costmap_2d
54 {
60 {
61 public:
79  const nav2_util::LifecycleNode::WeakPtr & parent,
80  std::string topic_name,
81  double observation_keep_time,
82  double expected_update_rate,
83  double min_obstacle_height, double max_obstacle_height, double obstacle_max_range,
84  double obstacle_min_range,
85  double raytrace_max_range, double raytrace_min_range, tf2_ros::Buffer & tf2_buffer,
86  std::string global_frame,
87  std::string sensor_frame,
88  tf2::Duration tf_tolerance);
89 
94 
100  void bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud);
101 
106  void getObservations(std::vector<Observation> & observations);
107 
112  bool isCurrent() const;
113 
117  inline void lock()
118  {
119  lock_.lock();
120  }
121 
125  inline void unlock()
126  {
127  lock_.unlock();
128  }
129 
133  void resetLastUpdated();
134 
135 private:
139  void purgeStaleObservations();
140 
141  rclcpp::Clock::SharedPtr clock_;
142  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
143  tf2_ros::Buffer & tf2_buffer_;
144  const rclcpp::Duration observation_keep_time_;
145  const rclcpp::Duration expected_update_rate_;
146  rclcpp::Time last_updated_;
147  std::string global_frame_;
148  std::string sensor_frame_;
149  std::list<Observation> observation_list_;
150  std::string topic_name_;
151  double min_obstacle_height_, max_obstacle_height_;
152  std::recursive_mutex lock_;
153  double obstacle_max_range_, obstacle_min_range_, raytrace_max_range_, raytrace_min_range_;
154  tf2::Duration tf_tolerance_;
155 };
156 } // namespace nav2_costmap_2d
157 #endif // NAV2_COSTMAP_2D__OBSERVATION_BUFFER_HPP_
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
ObservationBuffer(const nav2_util::LifecycleNode::WeakPtr &parent, std::string topic_name, double observation_keep_time, double expected_update_rate, double min_obstacle_height, double max_obstacle_height, double obstacle_max_range, double obstacle_min_range, double raytrace_max_range, double raytrace_min_range, tf2_ros::Buffer &tf2_buffer, std::string global_frame, std::string sensor_frame, tf2::Duration tf_tolerance)
Constructs an observation buffer.
~ObservationBuffer()
Destructor... cleans up.
void unlock()
Lock the observation buffer.
void lock()
Lock the observation buffer.
bool isCurrent() const
Check if the observation buffer is being update at its expected rate.
void getObservations(std::vector< Observation > &observations)
Pushes copies of all current observations onto the end of the vector passed in.
void bufferCloud(const sensor_msgs::msg::PointCloud2 &cloud)
Transforms a PointCloud to the global frame and buffers it Note: The burden is on the user to make su...
void resetLastUpdated()
Reset last updated timestamp.