Skip to content

Commit

Permalink
Revert "nav2_util::duration_from_seconds -> rclcpp::Duration::from_se…
Browse files Browse the repository at this point in the history
…conds (ros-navigation#1048)"

This reverts commit 7c473cd.
  • Loading branch information
Carl Delsey committed Sep 4, 2019
1 parent 6aecc6a commit 5053bfe
Show file tree
Hide file tree
Showing 11 changed files with 52 additions and 10 deletions.
1 change: 1 addition & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include "message_filters/subscriber.h"
#include "nav2_amcl/angleutils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/duration_conversions.hpp"
#include "nav2_amcl/pf/pf.hpp"
#include "nav2_util/string_utils.hpp"
#include "nav2_amcl/sensors/laser/laser.hpp"
Expand Down
3 changes: 2 additions & 1 deletion nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@

#include "pluginlib/class_list_macros.hpp"
#include "sensor_msgs/point_cloud2_iterator.hpp"
#include "nav2_util/duration_conversions.hpp"
#include "nav2_costmap_2d/costmap_math.hpp"

PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer)
Expand Down Expand Up @@ -211,7 +212,7 @@ void ObstacleLayer::onInitialize()
observation_subscribers_.push_back(sub);

observation_notifiers_.push_back(filter);
observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds(0.05));
observation_notifiers_.back()->setTolerance(nav2_util::duration_from_seconds(0.05));

} else {
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>> sub(
Expand Down
3 changes: 2 additions & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <vector>

#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav2_util/duration_conversions.hpp"
#include "nav2_util/execution_timer.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "nav2_util/robot_utils.hpp"
Expand Down Expand Up @@ -293,7 +294,7 @@ Costmap2DROS::getParameters()

// 2. The map publish frequency cannot be 0 (to avoid a divde-by-zero)
if (map_publish_frequency_ > 0) {
publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
publish_cycle_ = nav2_util::duration_from_seconds(1 / map_publish_frequency_);
} else {
publish_cycle_ = rclcpp::Duration(-1);
}
Expand Down
5 changes: 3 additions & 2 deletions nav2_costmap_2d/src/observation_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@

#include "tf2/convert.h"
#include "sensor_msgs/point_cloud2_iterator.hpp"
#include "nav2_util/duration_conversions.hpp"

namespace nav2_costmap_2d
{
Expand All @@ -53,8 +54,8 @@ ObservationBuffer::ObservationBuffer(
double raytrace_range, tf2_ros::Buffer & tf2_buffer, std::string global_frame,
std::string sensor_frame, double tf_tolerance)
: tf2_buffer_(tf2_buffer),
observation_keep_time_(rclcpp::Duration::from_seconds(observation_keep_time)),
expected_update_rate_(rclcpp::Duration::from_seconds(expected_update_rate)), nh_(nh),
observation_keep_time_(nav2_util::duration_from_seconds(observation_keep_time)),
expected_update_rate_(nav2_util::duration_from_seconds(expected_update_rate)), nh_(nh),
last_updated_(nh->now()), global_frame_(global_frame), sensor_frame_(sensor_frame),
topic_name_(topic_name),
min_obstacle_height_(min_obstacle_height), max_obstacle_height_(max_obstacle_height),
Expand Down
1 change: 1 addition & 0 deletions nav2_costmap_2d/test/integration/costmap_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include "tf2_ros/transform_listener.h"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_util/duration_conversions.hpp"

namespace nav2_costmap_2d
{
Expand Down
3 changes: 2 additions & 1 deletion nav2_dwb_controller/dwb_controller/src/progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "dwb_controller/progress_checker.hpp"
#include <cmath>
#include "dwb_core/exceptions.hpp"
#include "nav2_util/duration_conversions.hpp"

namespace dwb_controller
{
Expand All @@ -27,7 +28,7 @@ ProgressChecker::ProgressChecker(const rclcpp::Node::SharedPtr & node)
nh_->get_parameter_or("required_movement_radius", radius_, 0.5);
double time_allowance_param;
nh_->get_parameter_or("movement_time_allowance_", time_allowance_param, 10.0);
time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
time_allowance_ = nav2_util::duration_from_seconds(time_allowance_param);
}

void ProgressChecker::check(nav_2d_msgs::msg::Pose2DStamped & current_pose)
Expand Down
3 changes: 2 additions & 1 deletion nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include "nav_2d_utils/tf_help.hpp"
#include "nav2_util/lifecycle_node.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "nav2_util/duration_conversions.hpp"

namespace dwb_core
{
Expand Down Expand Up @@ -82,7 +83,7 @@ DWBLocalPlanner::on_configure(const rclcpp_lifecycle::State & state)

double transform_tolerance;
node_->get_parameter("transform_tolerance", transform_tolerance);
transform_tolerance_ = rclcpp::Duration::from_seconds(transform_tolerance);
transform_tolerance_ = nav2_util::duration_from_seconds(transform_tolerance);
RCLCPP_INFO(node_->get_logger(), "Setting transform_tolerance to %f", transform_tolerance);

node_->get_parameter("prune_plan", prune_plan_);
Expand Down
5 changes: 3 additions & 2 deletions nav2_dwb_controller/dwb_critics/src/oscillation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <cmath>
#include <string>
#include <vector>
#include "nav2_util/duration_conversions.hpp"
#include "nav_2d_utils/parameters.hpp"
#include "dwb_core/exceptions.hpp"
#include "pluginlib/class_list_macros.hpp"
Expand Down Expand Up @@ -93,7 +94,7 @@ void OscillationCritic::onInit()
oscillation_reset_dist_ = nav_2d_utils::searchAndGetParam(nh_, "oscillation_reset_dist", 0.05);
oscillation_reset_dist_sq_ = oscillation_reset_dist_ * oscillation_reset_dist_;
oscillation_reset_angle_ = nav_2d_utils::searchAndGetParam(nh_, "oscillation_reset_angle", 0.2);
oscillation_reset_time_ = rclcpp::Duration::from_seconds(
oscillation_reset_time_ = nav2_util::duration_from_seconds(
nav_2d_utils::searchAndGetParam(nh_, "oscillation_reset_time", -1.0));

nh_->declare_parameter(name_ + ".x_only_threshold", rclcpp::ParameterValue(0.05));
Expand Down Expand Up @@ -173,7 +174,7 @@ bool OscillationCritic::resetAvailable()
return true;
}
}
if (oscillation_reset_time_ >= rclcpp::Duration::from_seconds(0.0)) {
if (oscillation_reset_time_ >= nav2_util::duration_from_seconds(0.0)) {
auto t_diff = (nh_->now() - prev_reset_time_);
if (t_diff > oscillation_reset_time_) {
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "nav_2d_utils/parameters.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "dwb_core/exceptions.hpp"
#include "nav2_util/duration_conversions.hpp"

namespace dwb_plugins
{
Expand Down Expand Up @@ -86,7 +87,7 @@ dwb_msgs::msg::Trajectory2D LimitedAccelGenerator::generateTrajectory(
{
dwb_msgs::msg::Trajectory2D traj;
traj.velocity = cmd_vel;
traj.duration = rclcpp::Duration::from_seconds(sim_time_);
traj.duration = nav2_util::duration_from_seconds(sim_time_);
geometry_msgs::msg::Pose2D pose = start_pose;

std::vector<double> steps = getTimeSteps(cmd_vel);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include "nav_2d_utils/parameters.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "dwb_core/exceptions.hpp"
#include "nav2_util/duration_conversions.hpp"

using nav_2d_utils::loadParameterWithDeprecation;

Expand Down Expand Up @@ -147,7 +148,7 @@ dwb_msgs::msg::Trajectory2D StandardTrajectoryGenerator::generateTrajectory(
{
dwb_msgs::msg::Trajectory2D traj;
traj.velocity = cmd_vel;
traj.duration = rclcpp::Duration::from_seconds(sim_time_);
traj.duration = nav2_util::duration_from_seconds(sim_time_);
// simulate the trajectory
geometry_msgs::msg::Pose2D pose = start_pose;
nav_2d_msgs::msg::Twist2D vel = start_vel;
Expand Down
32 changes: 32 additions & 0 deletions nav2_util/include/nav2_util/duration_conversions.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
// Copyright (c) 2018 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NAV2_UTIL__DURATION_CONVERSIONS_HPP_
#define NAV2_UTIL__DURATION_CONVERSIONS_HPP_

#include "rclcpp/rclcpp.hpp"

namespace nav2_util
{

// TODO(crdelsey): This functionality should be part of the RCLCPP Duration
// interface. Once that gets integrated, this function can be removed.
inline rclcpp::Duration duration_from_seconds(double seconds)
{
return rclcpp::Duration(static_cast<int64_t>(seconds * 1e9)); // convert to ns
}

} // namespace nav2_util

#endif // NAV2_UTIL__DURATION_CONVERSIONS_HPP_

0 comments on commit 5053bfe

Please sign in to comment.