Skip to content

Commit d44596c

Browse files
authored
Use from_seconds() to avoid integer rounding (#1560) (#1561)
FootprintSubscriber constructor is using a Duration constructor that expects two integers for seconds and nanoseconds, but the footprint_timeout argument type is double, suggesting it should be floating point seconds. This uses `Duration::from_seconds()` to the timeout being rounded down to the next integer. Signed-off-by: Shane Loretz <[email protected]> Signed-off-by: Shane Loretz <[email protected]>
1 parent 8793b3a commit d44596c

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

nav2_costmap_2d/src/footprint_subscriber.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ FootprintSubscriber::FootprintSubscriber(
5555
node_logging_(node_logging),
5656
node_clock_(node_clock),
5757
topic_name_(topic_name),
58-
footprint_timeout_(rclcpp::Duration(footprint_timeout, 0.))
58+
footprint_timeout_(rclcpp::Duration::from_seconds(footprint_timeout))
5959
{
6060
footprint_sub_ = rclcpp::create_subscription<geometry_msgs::msg::PolygonStamped>(node_topics_,
6161
topic_name, rclcpp::SystemDefaultsQoS(),

0 commit comments

Comments
 (0)