Skip to content

Commit e6f9f55

Browse files
committed
Pass clock via constructor
Signed-off-by: Tim Clephas <[email protected]>
1 parent defb514 commit e6f9f55

File tree

3 files changed

+11
-8
lines changed

3 files changed

+11
-8
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <vector>
4444

4545
#include "rclcpp/logger.hpp"
46+
#include "rclcpp/clock.hpp"
4647
#include "nav2_costmap_2d/cost_values.hpp"
4748
#include "nav2_costmap_2d/layer.hpp"
4849
#include "nav2_costmap_2d/costmap_2d.hpp"
@@ -63,6 +64,7 @@ class LayeredCostmap
6364
*/
6465
LayeredCostmap(
6566
const rclcpp::Logger & logger,
67+
const rclcpp::Clock & clock,
6668
std::string global_frame,
6769
bool rolling_window,
6870
bool track_unknown);
@@ -223,6 +225,7 @@ class LayeredCostmap
223225

224226
private:
225227
rclcpp::Logger logger_;
228+
rclcpp::Clock clock_;
226229

227230
// primary_costmap_ is a bottom costmap used by plugins when costmap filters were enabled.
228231
// combined_costmap_ is a final costmap where all results produced by plugins and filters (if any)

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -157,7 +157,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
157157

158158
// Create the costmap itself
159159
layered_costmap_ = std::make_unique<LayeredCostmap>(
160-
get_logger(), global_frame_, rolling_window_, track_unknown_space_);
160+
get_logger(), *get_clock(), global_frame_, rolling_window_, track_unknown_space_);
161161

162162
if (!layered_costmap_->isSizeLocked()) {
163163
layered_costmap_->resizeMap(

nav2_costmap_2d/src/layered_costmap.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -56,11 +56,14 @@ namespace nav2_costmap_2d
5656

5757
LayeredCostmap::LayeredCostmap(
5858
const rclcpp::Logger & logger,
59+
const rclcpp::Clock & clock,
5960
std::string global_frame,
6061
bool rolling_window,
6162
bool track_unknown)
6263
: logger_(logger),
63-
primary_costmap_(), combined_costmap_(),
64+
clock_(clock),
65+
primary_costmap_(),
66+
combined_costmap_(),
6467
global_frame_(global_frame),
6568
rolling_window_(rolling_window),
6669
current_(false),
@@ -88,7 +91,8 @@ LayeredCostmap::LayeredCostmap(
8891
}
8992

9093
LayeredCostmap::LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown)
91-
: LayeredCostmap(rclcpp::get_logger("nav2_costmap_2d"), global_frame, rolling_window, track_unknown)
94+
: LayeredCostmap(rclcpp::get_logger("nav2_costmap_2d"), rclcpp::Clock{RCL_ROS_TIME}, global_frame,
95+
rolling_window, track_unknown)
9296
{
9397
}
9498

@@ -158,11 +162,7 @@ void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
158162
}
159163

160164
if (isOutofBounds(robot_x, robot_y)) {
161-
rclcpp::Clock clock{RCL_ROS_TIME};
162-
RCLCPP_WARN_THROTTLE(
163-
logger_,
164-
clock, 5000,
165-
"Robot is out of bounds of the costmap");
165+
RCLCPP_WARN_THROTTLE(logger_, clock_, 5000, "Robot is out of bounds of the costmap");
166166
}
167167

168168
if (plugins_.size() == 0 && filters_.size() == 0) {

0 commit comments

Comments
 (0)