diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp index 7af5e660cf2a5fc817c05f58400516308ba6fe87..ced4dd485720b0877d73a7d51c01e9c5630b9bed 100644 --- a/nav2_controller/src/nav2_controller.cpp +++ b/nav2_controller/src/nav2_controller.cpp @@ -339,7 +339,7 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path) auto end_pose = path.poses.back(); end_pose.header.frame_id = path.header.frame_id; - rclcpp::Duration tolerance(costmap_ros_->getTransformTolerance() * 1e9); + rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance())); nav_2d_utils::transformPose( costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(), end_pose, end_pose, tolerance); diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 7b7b3ea4be562c3c121e5907c1a21db3ad97d02e..70de2770f9aef3b917d250665e9b9b847fdf7f84 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -39,6 +39,7 @@ #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include <memory> +#include <chrono> #include <string> #include <vector> #include <utility> @@ -319,7 +320,7 @@ Costmap2DROS::getParameters() if (map_publish_frequency_ > 0) { publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_); } else { - publish_cycle_ = rclcpp::Duration(-1); + publish_cycle_ = rclcpp::Duration(-1s); } // 3. If the footprint has been specified, it must be in the correct format @@ -393,7 +394,7 @@ Costmap2DROS::mapUpdateLoop(double frequency) timer.end(); RCLCPP_DEBUG(get_logger(), "Map update time: %.9f", timer.elapsed_time_in_seconds()); - if (publish_cycle_ > rclcpp::Duration(0) && layered_costmap_->isInitialized()) { + if (publish_cycle_ > rclcpp::Duration(0s) && layered_costmap_->isInitialized()) { unsigned int x0, y0, xn, yn; layered_costmap_->getBounds(&x0, &xn, &y0, &yn); costmap_publisher_->updateBounds(x0, xn, y0, yn); diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp index 9d37eacf696f89cc547e9fc461340256b141c13a..8ac5b3958b8e0760b008215924a7239044f76a05 100644 --- a/nav2_costmap_2d/src/observation_buffer.cpp +++ b/nav2_costmap_2d/src/observation_buffer.cpp @@ -40,9 +40,11 @@ #include <list> #include <string> #include <vector> +#include <chrono> #include "tf2/convert.h" #include "sensor_msgs/point_cloud2_iterator.hpp" +using namespace std::chrono_literals; namespace nav2_costmap_2d { @@ -180,7 +182,7 @@ void ObservationBuffer::purgeStaleObservations() if (!observation_list_.empty()) { std::list<Observation>::iterator obs_it = observation_list_.begin(); // if we're keeping observations for no time... then we'll only keep one observation - if (observation_keep_time_ == rclcpp::Duration(0.0)) { + if (observation_keep_time_ == rclcpp::Duration(0.0s)) { observation_list_.erase(++obs_it, observation_list_.end()); return; } @@ -202,7 +204,7 @@ void ObservationBuffer::purgeStaleObservations() bool ObservationBuffer::isCurrent() const { - if (expected_update_rate_ == rclcpp::Duration(0.0)) { + if (expected_update_rate_ == rclcpp::Duration(0.0s)) { return true; } diff --git a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp index 619613c6785836f77f2586566fb765bf72d4e51a..1fc0885ecf50ce688f2cc9cd8554ae5e4de4b905 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp @@ -15,6 +15,7 @@ #include <string> #include <vector> #include <memory> +#include <chrono> #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" @@ -230,7 +231,7 @@ protected: { geometry_msgs::msg::TransformStamped tf_stamped; tf_stamped.header.frame_id = "map"; - tf_stamped.header.stamp = now() + rclcpp::Duration(1.0); + tf_stamped.header.stamp = now() + rclcpp::Duration(1.0ns); tf_stamped.child_frame_id = "base_link"; tf_stamped.transform.translation.x = x; tf_stamped.transform.translation.y = y; diff --git a/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp b/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp index 457213b50248ddf50055ed0274ca8c7c6e9ae2a1..bb2280801e228f9662ea00311fea9e11ba8f8607 100644 --- a/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp +++ b/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp @@ -37,8 +37,11 @@ #include <vector> #include <string> +#include <chrono> #include "dwb_core/trajectory_critic.hpp" +using namespace std::chrono_literals; // NOLINT + namespace dwb_critics { @@ -80,7 +83,7 @@ class OscillationCritic : public dwb_core::TrajectoryCritic { public: OscillationCritic() - : oscillation_reset_time_(0) {} + : oscillation_reset_time_(0s) {} void onInit() override; bool prepare( const geometry_msgs::msg::Pose2D & pose, const nav_2d_msgs::msg::Twist2D & vel, diff --git a/nav2_lifecycle_manager/src/lifecycle_manager.cpp b/nav2_lifecycle_manager/src/lifecycle_manager.cpp index 92a6279cb02270407b595a61eae30adb55f96b32..3f8832220319b0a40ddc374da84004cf33d0f71a 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager.cpp @@ -156,7 +156,10 @@ LifecycleManager::createBondConnection(const std::string & node_name) bond_map_[node_name]->setHeartbeatTimeout(timeout_s); bond_map_[node_name]->setHeartbeatPeriod(0.10); bond_map_[node_name]->start(); - if (!bond_map_[node_name]->waitUntilFormed(rclcpp::Duration(timeout_ns / 2))) { + if ( + !bond_map_[node_name]->waitUntilFormed( + rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2)))) + { RCLCPP_ERROR( get_logger(), "Server %s was unable to be reached after %0.2fs by bond. " diff --git a/nav2_recoveries/plugins/wait.cpp b/nav2_recoveries/plugins/wait.cpp index e9a27b4dda37364321635f74708e5933b68474c5..66bcabc1e91c29813f1f8f7d12d0cbf25dfb4ace 100644 --- a/nav2_recoveries/plugins/wait.cpp +++ b/nav2_recoveries/plugins/wait.cpp @@ -44,7 +44,7 @@ Status Wait::onCycleUpdate() auto time_left = std::chrono::duration_cast<std::chrono::nanoseconds>(wait_end_ - current_point).count(); - feedback_->time_left = rclcpp::Duration(time_left); + feedback_->time_left = rclcpp::Duration(rclcpp::Duration::from_nanoseconds(time_left)); action_server_->publish_feedback(feedback_); if (time_left > 0) { diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp index 396eafd4fa35f84d2592f161ce6852dbc614b064..e43992fbd4e163a83b97cf01bd1d663300c32572 100644 --- a/nav2_rviz_plugins/src/nav2_panel.cpp +++ b/nav2_rviz_plugins/src/nav2_panel.cpp @@ -20,6 +20,7 @@ #include <memory> #include <vector> #include <utility> +#include <chrono> #include "nav2_rviz_plugins/goal_common.hpp" #include "rviz_common/display_context.hpp" @@ -629,7 +630,7 @@ Nav2Panel::updateWpNavigationMarkers() arrow_marker.color.g = 255; arrow_marker.color.b = 0; arrow_marker.color.a = 1.0f; - arrow_marker.lifetime = rclcpp::Duration(0); + arrow_marker.lifetime = rclcpp::Duration(0s); arrow_marker.frame_locked = false; marker_array->markers.push_back(arrow_marker); @@ -647,7 +648,7 @@ Nav2Panel::updateWpNavigationMarkers() circle_marker.color.g = 0; circle_marker.color.b = 0; circle_marker.color.a = 1.0f; - circle_marker.lifetime = rclcpp::Duration(0); + circle_marker.lifetime = rclcpp::Duration(0s); circle_marker.frame_locked = false; marker_array->markers.push_back(circle_marker); @@ -666,7 +667,7 @@ Nav2Panel::updateWpNavigationMarkers() marker_text.color.g = 255; marker_text.color.b = 0; marker_text.color.a = 1.0f; - marker_text.lifetime = rclcpp::Duration(0); + marker_text.lifetime = rclcpp::Duration(0s); marker_text.frame_locked = false; marker_text.text = "wp_" + std::to_string(i + 1); marker_array->markers.push_back(marker_text); diff --git a/nav2_system_tests/src/planning/planner_tester.cpp b/nav2_system_tests/src/planning/planner_tester.cpp index 1367735aa268dc995b06ad8d5d07a88d9e150435..cfc5cbc3af0b154a0fc2f3874bc3627aed5292e8 100644 --- a/nav2_system_tests/src/planning/planner_tester.cpp +++ b/nav2_system_tests/src/planning/planner_tester.cpp @@ -133,7 +133,7 @@ void PlannerTester::updateRobotPosition(const geometry_msgs::msg::Point & positi } std::cout << now().nanoseconds() << std::endl; - base_transform_->header.stamp = now() + rclcpp::Duration(250000000); + base_transform_->header.stamp = now() + rclcpp::Duration(0.25s); base_transform_->transform.translation.x = position.x; base_transform_->transform.translation.y = position.y; base_transform_->transform.rotation.w = 1.0; diff --git a/nav2_system_tests/src/recoveries/backup/test_backup_recovery_launch.py b/nav2_system_tests/src/recoveries/backup/test_backup_recovery_launch.py index 7f23662f2e445d3c084a13a3300d05caac5d55c3..82739e309688e3aea97d4a782eca592f56f42304 100755 --- a/nav2_system_tests/src/recoveries/backup/test_backup_recovery_launch.py +++ b/nav2_system_tests/src/recoveries/backup/test_backup_recovery_launch.py @@ -59,13 +59,13 @@ def generate_launch_description(): # using a local copy of TB3 urdf file Node( package='tf2_ros', - node_executable='static_transform_publisher', + executable='static_transform_publisher', output='screen', arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']), Node( package='tf2_ros', - node_executable='static_transform_publisher', + executable='static_transform_publisher', output='screen', arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']), diff --git a/nav2_system_tests/src/recoveries/backup/test_backup_recovery_node.cpp b/nav2_system_tests/src/recoveries/backup/test_backup_recovery_node.cpp index 82c6effbd9e6c98eec81350f832b7953f5bfa251..f5efe16f9dceda95380aa139bc4d1c42d5680d0c 100644 --- a/nav2_system_tests/src/recoveries/backup/test_backup_recovery_node.cpp +++ b/nav2_system_tests/src/recoveries/backup/test_backup_recovery_node.cpp @@ -85,7 +85,7 @@ TEST_P(BackupRecoveryTestFixture, testBackupRecovery) // remain as a reminder to update this to a `false` case once the // recovery server returns true values. -INSTANTIATE_TEST_CASE_P( +INSTANTIATE_TEST_SUITE_P( BackupRecoveryTests, BackupRecoveryTestFixture, ::testing::Values( diff --git a/nav2_system_tests/src/recoveries/spin/test_spin_recovery_node.cpp b/nav2_system_tests/src/recoveries/spin/test_spin_recovery_node.cpp index cb83ed981e5cb6a573437485a6ff11b31cef5e91..d0e899029e998820eb9494d987c270651d9bfa5f 100644 --- a/nav2_system_tests/src/recoveries/spin/test_spin_recovery_node.cpp +++ b/nav2_system_tests/src/recoveries/spin/test_spin_recovery_node.cpp @@ -13,7 +13,6 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#include <gtest/gtest.h> #include <cmath> #include <tuple> #include <string> @@ -76,7 +75,7 @@ TEST_P(SpinRecoveryTestFixture, testSpinRecovery) EXPECT_EQ(true, success); } -INSTANTIATE_TEST_CASE_P( +INSTANTIATE_TEST_SUITE_P( SpinRecoveryTests, SpinRecoveryTestFixture, ::testing::Values( diff --git a/nav2_system_tests/src/recoveries/wait/test_wait_recovery_node.cpp b/nav2_system_tests/src/recoveries/wait/test_wait_recovery_node.cpp index 39ee9871d29383832b65a4c08ffce302b2c18d38..998808bf7ef748517c2a4e660ea005c9ad7b98f0 100644 --- a/nav2_system_tests/src/recoveries/wait/test_wait_recovery_node.cpp +++ b/nav2_system_tests/src/recoveries/wait/test_wait_recovery_node.cpp @@ -80,7 +80,7 @@ TEST_P(WaitRecoveryTestFixture, testSWaitRecovery) EXPECT_EQ(true, success); } -INSTANTIATE_TEST_CASE_P( +INSTANTIATE_TEST_SUITE_P( WaitRecoveryTests, WaitRecoveryTestFixture, ::testing::Values( diff --git a/nav2_waypoint_follower/plugins/input_at_waypoint.cpp b/nav2_waypoint_follower/plugins/input_at_waypoint.cpp index 98dbfeaa0cb2d989d05867e2769c89f12dc2b07e..32c33cfc03d20880d5e5d03bb34e29c22524caa9 100644 --- a/nav2_waypoint_follower/plugins/input_at_waypoint.cpp +++ b/nav2_waypoint_follower/plugins/input_at_waypoint.cpp @@ -39,7 +39,7 @@ void InputAtWaypoint::initialize( const std::string & plugin_name) { auto node = parent.lock(); - + if (!node) { throw std::runtime_error{"Failed to lock node in input at waypoint plugin!"}; } diff --git a/smac_planner/test/test_a_star.cpp b/smac_planner/test/test_a_star.cpp index a1e5dcf2080fd2c800ee32244c79d564689d8b84..091ee0cf00ac3b813797cbf0ce1b9a71b9d9fbc9 100644 --- a/smac_planner/test/test_a_star.cpp +++ b/smac_planner/test/test_a_star.cpp @@ -153,7 +153,7 @@ TEST(AStarTest, test_a_star_se2) EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); // check path is the right size and collision free - EXPECT_EQ(num_it, 61); + EXPECT_EQ(num_it, 44); EXPECT_EQ(path.size(), 75u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); diff --git a/tools/underlay.repos b/tools/underlay.repos index 73d6b1f1e281903bf7a38adf7e217d15c2559705..6df91bf25fe9a942e8427b8b374de55493a4128a 100644 --- a/tools/underlay.repos +++ b/tools/underlay.repos @@ -21,8 +21,8 @@ repositories: version: ros2 ros/bond_core: type: git - url: https://github.com/ros/bond_core.git - version: ros2 + url: https://github.com/stevemacenski/bond_core.git + version: fix_deprecation_warning ompl/ompl: type: git url: https://github.com/ompl/ompl.git