diff --git a/nav2_controller/CMakeLists.txt b/nav2_controller/CMakeLists.txt index 56ea5d7e794..93885ef7efc 100644 --- a/nav2_controller/CMakeLists.txt +++ b/nav2_controller/CMakeLists.txt @@ -11,8 +11,6 @@ find_package(nav2_common REQUIRED) find_package(nav2_costmap_2d REQUIRED) find_package(nav2_msgs REQUIRED) find_package(nav2_util REQUIRED) -find_package(nav_2d_msgs REQUIRED) -find_package(nav_2d_utils REQUIRED) find_package(pluginlib REQUIRED) find_package(rcl_interfaces REQUIRED) find_package(rclcpp REQUIRED) @@ -42,9 +40,6 @@ target_link_libraries(${library_name} PUBLIC ${nav2_msgs_TARGETS} nav2_util::nav2_util_core nav2_ros_common::nav2_ros_common - ${nav_2d_msgs_TARGETS} - nav_2d_utils::conversions - nav_2d_utils::tf_help pluginlib::pluginlib rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle @@ -86,7 +81,6 @@ target_link_libraries(simple_progress_checker PUBLIC ) target_link_libraries(simple_progress_checker PRIVATE nav2_util::nav2_util_core - nav_2d_utils::conversions pluginlib::pluginlib ) @@ -107,7 +101,6 @@ target_link_libraries(pose_progress_checker PUBLIC target_link_libraries(pose_progress_checker PRIVATE angles::angles nav2_util::nav2_util_core - nav_2d_utils::conversions pluginlib::pluginlib ) @@ -218,8 +211,6 @@ ament_export_dependencies( nav2_costmap_2d nav2_msgs nav2_util - nav_2d_msgs - nav_2d_utils pluginlib rclcpp rclcpp_lifecycle diff --git a/nav2_controller/include/nav2_controller/controller_server.hpp b/nav2_controller/include/nav2_controller/controller_server.hpp index a838854a52b..b68c8e5bb94 100644 --- a/nav2_controller/include/nav2_controller/controller_server.hpp +++ b/nav2_controller/include/nav2_controller/controller_server.hpp @@ -29,10 +29,10 @@ #include "tf2_ros/transform_listener.hpp" #include "nav2_msgs/action/follow_path.hpp" #include "nav2_msgs/msg/speed_limit.hpp" -#include "nav_2d_utils/odom_subscriber.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_ros_common/simple_action_server.hpp" #include "nav2_util/robot_utils.hpp" +#include "nav2_util/odometry_utils.hpp" #include "nav2_util/twist_publisher.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" @@ -208,12 +208,12 @@ class ControllerServer : public nav2::LifecycleNode * @param Twist The current Twist from odometry * @return Twist Twist after thresholds applied */ - nav_2d_msgs::msg::Twist2D getThresholdedTwist(const nav_2d_msgs::msg::Twist2D & twist) + geometry_msgs::msg::Twist getThresholdedTwist(const geometry_msgs::msg::Twist & twist) { - nav_2d_msgs::msg::Twist2D twist_thresh; - twist_thresh.x = getThresholdedVelocity(twist.x, min_x_velocity_threshold_); - twist_thresh.y = getThresholdedVelocity(twist.y, min_y_velocity_threshold_); - twist_thresh.theta = getThresholdedVelocity(twist.theta, min_theta_velocity_threshold_); + geometry_msgs::msg::Twist twist_thresh; + twist_thresh.linear.x = getThresholdedVelocity(twist.linear.x, min_x_velocity_threshold_); + twist_thresh.linear.y = getThresholdedVelocity(twist.linear.y, min_y_velocity_threshold_); + twist_thresh.angular.z = getThresholdedVelocity(twist.angular.z, min_theta_velocity_threshold_); return twist_thresh; } @@ -233,7 +233,7 @@ class ControllerServer : public nav2::LifecycleNode std::unique_ptr costmap_thread_; // Publishers and subscribers - std::unique_ptr odom_sub_; + std::unique_ptr odom_sub_; std::unique_ptr vel_publisher_; nav2::Subscription::SharedPtr speed_limit_sub_; diff --git a/nav2_controller/package.xml b/nav2_controller/package.xml index b5be342451c..9360c10d05f 100644 --- a/nav2_controller/package.xml +++ b/nav2_controller/package.xml @@ -18,8 +18,6 @@ nav2_costmap_2d nav2_msgs nav2_util - nav_2d_msgs - nav_2d_utils pluginlib rcl_interfaces rclcpp diff --git a/nav2_controller/plugins/pose_progress_checker.cpp b/nav2_controller/plugins/pose_progress_checker.cpp index 453d20992e8..a891104cac0 100644 --- a/nav2_controller/plugins/pose_progress_checker.cpp +++ b/nav2_controller/plugins/pose_progress_checker.cpp @@ -18,7 +18,6 @@ #include #include #include "angles/angles.h" -#include "nav_2d_utils/conversions.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_controller/plugins/simple_progress_checker.cpp b/nav2_controller/plugins/simple_progress_checker.cpp index 2e219cdeee8..df3cb77df69 100644 --- a/nav2_controller/plugins/simple_progress_checker.cpp +++ b/nav2_controller/plugins/simple_progress_checker.cpp @@ -17,7 +17,6 @@ #include #include #include -#include "nav_2d_utils/conversions.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_controller/plugins/test/CMakeLists.txt b/nav2_controller/plugins/test/CMakeLists.txt index cd8048513d4..ba0ce9eb2d5 100644 --- a/nav2_controller/plugins/test/CMakeLists.txt +++ b/nav2_controller/plugins/test/CMakeLists.txt @@ -1,5 +1,5 @@ ament_add_gtest(pctest progress_checker.cpp) -target_link_libraries(pctest simple_progress_checker pose_progress_checker nav_2d_utils::conversions) +target_link_libraries(pctest simple_progress_checker pose_progress_checker) ament_add_gtest(gctest goal_checker.cpp) -target_link_libraries(gctest simple_goal_checker stopped_goal_checker nav_2d_utils::conversions) +target_link_libraries(gctest simple_goal_checker stopped_goal_checker) diff --git a/nav2_controller/plugins/test/goal_checker.cpp b/nav2_controller/plugins/test/goal_checker.cpp index 4730aeb3a04..1aba1ba80bb 100644 --- a/nav2_controller/plugins/test/goal_checker.cpp +++ b/nav2_controller/plugins/test/goal_checker.cpp @@ -38,7 +38,6 @@ #include "gtest/gtest.h" #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "nav2_controller/plugins/stopped_goal_checker.hpp" -#include "nav_2d_utils/conversions.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "eigen3/Eigen/Geometry" diff --git a/nav2_controller/plugins/test/progress_checker.cpp b/nav2_controller/plugins/test/progress_checker.cpp index 0791b9e9c27..293daf13a25 100644 --- a/nav2_controller/plugins/test/progress_checker.cpp +++ b/nav2_controller/plugins/test/progress_checker.cpp @@ -38,7 +38,6 @@ #include "gtest/gtest.h" #include "nav2_controller/plugins/simple_progress_checker.hpp" #include "nav2_controller/plugins/pose_progress_checker.hpp" -#include "nav_2d_utils/conversions.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/geometry_utils.hpp" diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index 26187087ec1..66b62e667e2 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -21,8 +21,6 @@ #include "lifecycle_msgs/msg/state.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "nav_2d_utils/conversions.hpp" -#include "nav_2d_utils/tf_help.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_controller/controller_server.hpp" @@ -65,6 +63,9 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) declare_parameter("publish_zero_velocity", rclcpp::ParameterValue(true)); declare_parameter("costmap_update_timeout", 0.30); // 300ms + declare_parameter("odom_topic", rclcpp::ParameterValue("odom")); + declare_parameter("odom_duration", rclcpp::ParameterValue(0.3)); + // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( "local_costmap", std::string{get_namespace()}, @@ -125,8 +126,11 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_); RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_); - std::string speed_limit_topic; + std::string speed_limit_topic, odom_topic; get_parameter("speed_limit_topic", speed_limit_topic); + get_parameter("odom_topic", odom_topic); + double odom_duration; + get_parameter("odom_duration", odom_duration); get_parameter("failure_tolerance", failure_tolerance_); get_parameter("use_realtime_priority", use_realtime_priority_); get_parameter("publish_zero_velocity", publish_zero_velocity_); @@ -219,7 +223,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Controller Server has %s controllers available.", controller_ids_concat_.c_str()); - odom_sub_ = std::make_unique(node); + odom_sub_ = std::make_unique(node, odom_duration, odom_topic); vel_publisher_ = std::make_unique(node, "cmd_vel"); double costmap_update_timeout_dbl; @@ -624,7 +628,7 @@ void ControllerServer::computeAndPublishVelocity() throw nav2_core::FailedToMakeProgress("Failed to make progress"); } - nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist()); + geometry_msgs::msg::Twist twist = getThresholdedTwist(odom_sub_->getRawTwist()); geometry_msgs::msg::TwistStamped cmd_vel_2d; @@ -632,7 +636,7 @@ void ControllerServer::computeAndPublishVelocity() cmd_vel_2d = controllers_[current_controller_]->computeVelocityCommands( pose, - nav_2d_utils::twist2Dto3D(twist), + twist, goal_checkers_[current_goal_checker_].get()); last_valid_cmd_time_ = now(); cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID(); @@ -665,10 +669,9 @@ void ControllerServer::computeAndPublishVelocity() // Find the closest pose to current pose on global path geometry_msgs::msg::PoseStamped robot_pose_in_path_frame; - rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance())); - if (!nav_2d_utils::transformPose( - costmap_ros_->getTfBuffer(), current_path_.header.frame_id, pose, - robot_pose_in_path_frame, tolerance)) + if (!nav2_util::transformPoseInTargetFrame( + pose, robot_pose_in_path_frame, *costmap_ros_->getTfBuffer(), + current_path_.header.frame_id, costmap_ros_->getTransformTolerance())) { throw nav2_core::ControllerTFError("Failed to transform robot pose to path frame"); } @@ -793,14 +796,12 @@ bool ControllerServer::isGoalReached() return false; } - nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist()); - geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(twist); + geometry_msgs::msg::Twist velocity = getThresholdedTwist(odom_sub_->getRawTwist()); geometry_msgs::msg::PoseStamped transformed_end_pose; - rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance())); - nav_2d_utils::transformPose( - costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(), - end_pose_, transformed_end_pose, tolerance); + nav2_util::transformPoseInTargetFrame( + end_pose_, transformed_end_pose, *costmap_ros_->getTfBuffer(), + costmap_ros_->getGlobalFrameID(), costmap_ros_->getTransformTolerance()); return goal_checkers_[current_goal_checker_]->isGoalReached( pose.pose, transformed_end_pose.pose, diff --git a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp index eb1497f21db..4538b2e447d 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp @@ -27,7 +27,7 @@ #include "nav2_ros_common/node_utils.hpp" #include "nav2_ros_common/simple_action_server.hpp" #include "nav2_util/twist_publisher.hpp" -#include "nav_2d_utils/odom_subscriber.hpp" +#include "nav2_util/odometry_utils.hpp" #include "opennav_docking/controller.hpp" #include "opennav_docking/utils.hpp" #include "opennav_docking/types.hpp" @@ -264,7 +264,7 @@ class DockingServer : public nav2::LifecycleNode rclcpp::Time action_start_time_; std::unique_ptr vel_publisher_; - std::unique_ptr odom_sub_; + std::unique_ptr odom_sub_; typename DockingActionServer::SharedPtr docking_action_server_; typename UndockingActionServer::SharedPtr undocking_action_server_; diff --git a/nav2_docking/opennav_docking/src/controller.cpp b/nav2_docking/opennav_docking/src/controller.cpp index 9048c70a29a..7838158f8af 100644 --- a/nav2_docking/opennav_docking/src/controller.cpp +++ b/nav2_docking/opennav_docking/src/controller.cpp @@ -19,7 +19,6 @@ #include "opennav_docking/controller.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_ros_common/node_utils.hpp" -#include "nav_2d_utils/conversions.hpp" #include "tf2/utils.hpp" namespace opennav_docking diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index 3584af4e9d3..17dc1c28da3 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -42,6 +42,7 @@ DockingServer::DockingServer(const rclcpp::NodeOptions & options) declare_parameter("dock_backwards", rclcpp::PARAMETER_BOOL); declare_parameter("dock_prestaging_tolerance", 0.5); declare_parameter("odom_topic", "odom"); + declare_parameter("odom_duration", 0.3); declare_parameter("rotation_angular_tolerance", 0.05); } @@ -83,7 +84,9 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state) // Create odom subscriber for backward blind docking std::string odom_topic; get_parameter("odom_topic", odom_topic); - odom_sub_ = std::make_unique(node, odom_topic); + double odom_duration; + get_parameter("odom_duration", odom_duration); + odom_sub_ = std::make_unique(node, odom_duration, odom_topic); // Create the action servers for dock / undock docking_action_server_ = node->create_action_server( @@ -464,7 +467,7 @@ void DockingServer::rotateToDock(const geometry_msgs::msg::PoseStamped & dock_po } auto current_vel = std::make_unique(); - current_vel->twist.angular.z = odom_sub_->getTwist().theta; + current_vel->twist.angular.z = odom_sub_->getRawTwist().angular.z; auto command = std::make_unique(); command->header = robot_pose.header; diff --git a/nav2_dwb_controller/dwb_core/CMakeLists.txt b/nav2_dwb_controller/dwb_core/CMakeLists.txt index b57c2291a51..00789a46e3d 100644 --- a/nav2_dwb_controller/dwb_core/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_core/CMakeLists.txt @@ -45,7 +45,6 @@ target_link_libraries(dwb_core PUBLIC nav2_util::nav2_util_core ${nav_2d_msgs_TARGETS} nav_2d_utils::conversions - nav_2d_utils::tf_help ${nav_msgs_TARGETS} pluginlib::pluginlib rclcpp::rclcpp diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp index 41120a7c48a..63013bd091e 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp @@ -199,7 +199,7 @@ class DWBLocalPlanner : public nav2_core::Controller bool prune_plan_; double prune_distance_; bool debug_trajectory_details_; - rclcpp::Duration transform_tolerance_{0, 0}; + double transform_tolerance_{0}; bool shorten_transformed_plan_; double forward_prune_distance_; diff --git a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp index e539c98819a..5c1b47322a6 100644 --- a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp +++ b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp @@ -44,7 +44,6 @@ #include "dwb_msgs/msg/critic_score.hpp" #include "nav_2d_msgs/msg/twist2_d.hpp" #include "nav_2d_utils/conversions.hpp" -#include "nav_2d_utils/tf_help.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_ros_common/node_utils.hpp" @@ -112,8 +111,7 @@ void DWBLocalPlanner::configure( std::string traj_generator_name; double transform_tolerance; - node->get_parameter(dwb_plugin_name_ + ".transform_tolerance", transform_tolerance); - transform_tolerance_ = rclcpp::Duration::from_seconds(transform_tolerance); + node->get_parameter(dwb_plugin_name_ + ".transform_tolerance", transform_tolerance_); RCLCPP_INFO(logger_, "Setting transform_tolerance to %f", transform_tolerance); node->get_parameter(dwb_plugin_name_ + ".prune_plan", prune_plan_); @@ -293,9 +291,9 @@ DWBLocalPlanner::prepareGlobalPlan( goal_pose.header.frame_id = global_plan_.header.frame_id; goal_pose.pose = global_plan_.poses.back().pose; - nav_2d_utils::transformPose( - tf_, costmap_ros_->getGlobalFrameID(), goal_pose, - goal_pose, transform_tolerance_); + nav2_util::transformPoseInTargetFrame( + goal_pose, goal_pose, *tf_, + costmap_ros_->getGlobalFrameID(), transform_tolerance_); } nav_2d_msgs::msg::Twist2DStamped @@ -470,9 +468,9 @@ DWBLocalPlanner::transformGlobalPlan( // let's get the pose of the robot in the frame of the plan geometry_msgs::msg::PoseStamped robot_pose; - if (!nav_2d_utils::transformPose( - tf_, global_plan_.header.frame_id, pose, - robot_pose, transform_tolerance_)) + if (!nav2_util::transformPoseInTargetFrame( + pose, robot_pose, *tf_, + global_plan_.header.frame_id, transform_tolerance_)) { throw nav2_core:: ControllerTFError("Unable to transform robot pose into global plan's frame"); @@ -538,9 +536,9 @@ DWBLocalPlanner::transformGlobalPlan( // frame to local auto transformGlobalPoseToLocal = [&](const auto & global_plan_pose) { geometry_msgs::msg::PoseStamped transformed_pose; - nav_2d_utils::transformPose( - tf_, transformed_plan.header.frame_id, - global_plan_pose, transformed_pose, transform_tolerance_); + nav2_util::transformPoseInTargetFrame( + global_plan_pose, transformed_pose, *tf_, + transformed_plan.header.frame_id, transform_tolerance_); return transformed_pose; }; diff --git a/nav2_dwb_controller/dwb_critics/src/goal_align.cpp b/nav2_dwb_controller/dwb_critics/src/goal_align.cpp index 1ae85c2e1dd..f8b713c032f 100644 --- a/nav2_dwb_controller/dwb_critics/src/goal_align.cpp +++ b/nav2_dwb_controller/dwb_critics/src/goal_align.cpp @@ -37,7 +37,6 @@ #include #include "dwb_critics/alignment_util.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav_2d_utils/parameters.hpp" namespace dwb_critics { @@ -52,9 +51,8 @@ void GoalAlignCritic::onInit() throw std::runtime_error{"Failed to lock node"}; } - forward_point_distance_ = nav_2d_utils::searchAndGetParam( - node, - dwb_plugin_name_ + "." + name_ + ".forward_point_distance", 0.325); + forward_point_distance_ = node->declare_or_get_parameter(dwb_plugin_name_ + "." + name_ + + ".forward_point_distance", 0.325); } bool GoalAlignCritic::prepare( diff --git a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp index bad8e40e3ff..170a9764c1f 100644 --- a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp +++ b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp @@ -37,7 +37,6 @@ #include #include #include -#include "nav_2d_utils/parameters.hpp" #include "nav2_ros_common/node_utils.hpp" #include "dwb_core/exceptions.hpp" #include "pluginlib/class_list_macros.hpp" @@ -99,16 +98,13 @@ void OscillationCritic::onInit() clock_ = node->get_clock(); - oscillation_reset_dist_ = nav_2d_utils::searchAndGetParam( - node, - dwb_plugin_name_ + "." + name_ + ".oscillation_reset_dist", 0.05); + oscillation_reset_dist_ = node->declare_or_get_parameter(dwb_plugin_name_ + "." + name_ + + ".oscillation_reset_dist", 0.05); oscillation_reset_dist_sq_ = oscillation_reset_dist_ * oscillation_reset_dist_; - oscillation_reset_angle_ = nav_2d_utils::searchAndGetParam( - node, + oscillation_reset_angle_ = node->declare_or_get_parameter( dwb_plugin_name_ + "." + name_ + ".oscillation_reset_angle", 0.2); oscillation_reset_time_ = rclcpp::Duration::from_seconds( - nav_2d_utils::searchAndGetParam( - node, + node->declare_or_get_parameter( dwb_plugin_name_ + "." + name_ + ".oscillation_reset_time", -1.0)); nav2::declare_parameter_if_not_declared( diff --git a/nav2_dwb_controller/dwb_critics/src/path_align.cpp b/nav2_dwb_controller/dwb_critics/src/path_align.cpp index 6c4b28ea6f5..d91414586dd 100644 --- a/nav2_dwb_controller/dwb_critics/src/path_align.cpp +++ b/nav2_dwb_controller/dwb_critics/src/path_align.cpp @@ -37,7 +37,6 @@ #include #include "dwb_critics/alignment_util.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav_2d_utils/parameters.hpp" namespace dwb_critics { @@ -52,8 +51,7 @@ void PathAlignCritic::onInit() throw std::runtime_error{"Failed to lock node"}; } - forward_point_distance_ = nav_2d_utils::searchAndGetParam( - node, + forward_point_distance_ = node->declare_or_get_parameter( dwb_plugin_name_ + "." + name_ + ".forward_point_distance", 0.325); } diff --git a/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp b/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp index f4323188b18..34f2ae95335 100644 --- a/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp +++ b/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp @@ -35,7 +35,6 @@ #include "dwb_critics/rotate_to_goal.hpp" #include #include -#include "nav_2d_utils/parameters.hpp" #include "dwb_core/exceptions.hpp" #include "pluginlib/class_list_macros.hpp" #include "dwb_core/trajectory_utils.hpp" @@ -58,19 +57,15 @@ void RotateToGoalCritic::onInit() throw std::runtime_error{"Failed to lock node"}; } - xy_goal_tolerance_ = nav_2d_utils::searchAndGetParam( - node, + xy_goal_tolerance_ = node->declare_or_get_parameter( dwb_plugin_name_ + ".xy_goal_tolerance", 0.25); xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_; - double stopped_xy_velocity = nav_2d_utils::searchAndGetParam( - node, + double stopped_xy_velocity = node->declare_or_get_parameter( dwb_plugin_name_ + ".trans_stopped_velocity", 0.25); stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity; - slowing_factor_ = nav_2d_utils::searchAndGetParam( - node, + slowing_factor_ = node->declare_or_get_parameter( dwb_plugin_name_ + "." + name_ + ".slowing_factor", 5.0); - lookahead_time_ = nav_2d_utils::searchAndGetParam( - node, + lookahead_time_ = node->declare_or_get_parameter( dwb_plugin_name_ + "." + name_ + ".lookahead_time", -1.0); reset(); } diff --git a/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp b/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp index dde49133011..c1152bc3f5b 100644 --- a/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp @@ -38,7 +38,6 @@ #include #include -#include "nav_2d_utils/parameters.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" diff --git a/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp b/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp index 24d1c255973..4c096f7e1f1 100644 --- a/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp @@ -36,7 +36,6 @@ #include #include #include -#include "nav_2d_utils/parameters.hpp" #include "pluginlib/class_list_macros.hpp" #include "dwb_core/exceptions.hpp" #include "nav2_ros_common/node_utils.hpp" @@ -65,8 +64,7 @@ void LimitedAccelGenerator::initialize( RCLCPP_WARN( rclcpp::get_logger("LimitedAccelGenerator"), "'sim_period' parameter is not set for %s", plugin_name.c_str()); - double controller_frequency = nav_2d_utils::searchAndGetParam( - nh, "controller_frequency", 20.0); + double controller_frequency = nh->declare_or_get_parameter("controller_frequency", 20.0); if (controller_frequency > 0) { acceleration_time_ = 1.0 / controller_frequency; } else { diff --git a/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp b/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp index 8e68a399f08..a11dd8ece0b 100644 --- a/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp @@ -38,7 +38,6 @@ #include #include #include "dwb_plugins/xy_theta_iterator.hpp" -#include "nav_2d_utils/parameters.hpp" #include "pluginlib/class_list_macros.hpp" #include "dwb_core/exceptions.hpp" #include "nav2_ros_common/node_utils.hpp" diff --git a/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp b/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp index c319bef4a72..01dab35cb7b 100644 --- a/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp @@ -38,7 +38,6 @@ #include #include -#include "nav_2d_utils/parameters.hpp" #include "nav2_ros_common/node_utils.hpp" namespace dwb_plugins diff --git a/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt b/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt index c3005dffd6c..7aad657a142 100644 --- a/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt +++ b/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt @@ -56,28 +56,7 @@ target_link_libraries(path_ops PRIVATE ${geometry_msgs_TARGETS} ) -add_library(tf_help SHARED - src/tf_help.cpp -) -target_include_directories(tf_help - PUBLIC - "$" - "$" -) -target_link_libraries(tf_help PUBLIC - conversions - ${geometry_msgs_TARGETS} - ${nav_2d_msgs_TARGETS} - rclcpp::rclcpp - nav2_ros_common::nav2_ros_common - tf2::tf2 - tf2_geometry_msgs::tf2_geometry_msgs - tf2_ros::tf2_ros - rclcpp_lifecycle::rclcpp_lifecycle - rcl_lifecycle::rcl_lifecycle -) - -install(TARGETS conversions path_ops tf_help +install(TARGETS conversions path_ops EXPORT ${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib @@ -101,7 +80,7 @@ if(BUILD_TESTING) endif() ament_export_include_directories(include/${PROJECT_NAME}) -ament_export_libraries(conversions path_ops tf_help) +ament_export_libraries(conversions path_ops) ament_export_dependencies( geometry_msgs nav_2d_msgs diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp index 35f3ec2018f..3a30fd03050 100644 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp +++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp @@ -49,10 +49,6 @@ namespace nav_2d_utils { geometry_msgs::msg::Twist twist2Dto3D(const nav_2d_msgs::msg::Twist2D & cmd_vel_2d); nav_2d_msgs::msg::Twist2D twist3Dto2D(const geometry_msgs::msg::Twist & cmd_vel); -geometry_msgs::msg::PoseStamped poseToPoseStamped( - const geometry_msgs::msg::Pose & pose, - const std::string & frame, const rclcpp::Time & stamp); -nav_msgs::msg::Path posesToPath(const std::vector & poses); nav_msgs::msg::Path posesToPath( const std::vector & poses, const std::string & frame, const rclcpp::Time & stamp); diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp deleted file mode 100644 index 2f989e71f2f..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp +++ /dev/null @@ -1,100 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2017, Locus Robotics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef NAV_2D_UTILS__ODOM_SUBSCRIBER_HPP_ -#define NAV_2D_UTILS__ODOM_SUBSCRIBER_HPP_ - -#include -#include -#include -#include -#include "nav_2d_msgs/msg/twist2_d_stamped.hpp" -#include "nav_msgs/msg/odometry.hpp" -#include "nav2_ros_common/lifecycle_node.hpp" -#include "rclcpp/rclcpp.hpp" -#include "nav2_ros_common/node_utils.hpp" - -namespace nav_2d_utils -{ - -/** - * @class OdomSubscriber - * Wrapper for some common odometry operations. Subscribes to the topic with a mutex. - */ -class OdomSubscriber -{ -public: - /** - * @brief Constructor that subscribes to an Odometry topic - * - * @param nh NodeHandle for creating subscriber - * @param default_topic Name of the topic that will be loaded of the odom_topic param is not set. - */ - explicit OdomSubscriber( - nav2::LifecycleNode::SharedPtr nh, - std::string default_topic = "odom") - { - nav2::declare_parameter_if_not_declared( - nh, "odom_topic", rclcpp::ParameterValue(default_topic)); - - std::string odom_topic; - nh->get_parameter_or("odom_topic", odom_topic, default_topic); - odom_sub_ = - nh->create_subscription( - odom_topic, - std::bind(&OdomSubscriber::odomCallback, this, std::placeholders::_1)); - } - - inline nav_2d_msgs::msg::Twist2D getTwist() {return odom_vel_.velocity;} - inline nav_2d_msgs::msg::Twist2DStamped getTwistStamped() {return odom_vel_;} - -protected: - void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg) - { - // ROS_INFO_ONCE("odom received!"); - std::lock_guard lock(odom_mutex_); - odom_vel_.header = msg->header; - odom_vel_.velocity.x = msg->twist.twist.linear.x; - odom_vel_.velocity.y = msg->twist.twist.linear.y; - odom_vel_.velocity.theta = msg->twist.twist.angular.z; - } - - nav2::Subscription::SharedPtr odom_sub_; - nav_2d_msgs::msg::Twist2DStamped odom_vel_; - std::mutex odom_mutex_; -}; - -} // namespace nav_2d_utils - -#endif // NAV_2D_UTILS__ODOM_SUBSCRIBER_HPP_ diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp deleted file mode 100644 index 09b039487e0..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp +++ /dev/null @@ -1,76 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2017, Locus Robotics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef NAV_2D_UTILS__PARAMETERS_HPP_ -#define NAV_2D_UTILS__PARAMETERS_HPP_ - -#include -#include - -#include "rclcpp/rclcpp.hpp" -#include "nav2_ros_common/lifecycle_node.hpp" -#include "nav2_ros_common/node_utils.hpp" - -// TODO(crdelsey): Remove when code is re-enabled -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-parameter" -namespace nav_2d_utils -{ - -/** - * @brief Search for a parameter and load it, or use the default value - * - * This templated function shortens a commonly used ROS pattern in which you - * search for a parameter and get its value if it exists, otherwise returning a default value. - * - * @param nh NodeHandle to start the parameter search from - * @param param_name Name of the parameter to search for - * @param default_value Value to return if not found - * @return Value of parameter if found, otherwise the default_value - */ -template -param_t searchAndGetParam( - const nav2::LifecycleNode::SharedPtr & nh, const std::string & param_name, - const param_t & default_value) -{ - nav2::declare_parameter_if_not_declared( - nh, param_name, - rclcpp::ParameterValue(default_value)); - return nh->get_parameter(param_name).get_value(); -} - -} // namespace nav_2d_utils -#pragma GCC diagnostic pop - -#endif // NAV_2D_UTILS__PARAMETERS_HPP_ diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp deleted file mode 100644 index 3f5fadcd4aa..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/tf_help.hpp +++ /dev/null @@ -1,85 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2017, Locus Robotics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef NAV_2D_UTILS__TF_HELP_HPP_ -#define NAV_2D_UTILS__TF_HELP_HPP_ - -#include -#include -#include "tf2_ros/buffer.hpp" -#include "nav_2d_utils/conversions.hpp" -#include "geometry_msgs/msg/pose_stamped.hpp" -#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" - -namespace nav_2d_utils -{ -/** - * @brief Transform a PoseStamped from one frame to another while catching exceptions - * - * Also returns immediately if the frames are equal. - * @param tf Smart pointer to TFListener - * @param frame Frame to transform the pose into - * @param in_pose Pose to transform - * @param out_pose Place to store the resulting transformed pose - * @return True if successful transform - */ -bool transformPose( - const std::shared_ptr tf, - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose, - rclcpp::Duration & transform_tolerance -); - -/** - * @brief Transform a PoseStamped from one frame to another while catching exceptions - * - * Also returns immediately if the frames are equal. - * @param tf Smart pointer to TFListener - * @param frame Frame to transform the pose into - * @param in_pose Pose to transform - * @param out_pose Place to store the resulting transformed pose - * @return True if successful transform - */ -bool transformPose( - const std::shared_ptr tf, - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose, - rclcpp::Duration & transform_tolerance -); - -} // namespace nav_2d_utils - -#endif // NAV_2D_UTILS__TF_HELP_HPP_ diff --git a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp index 4ec9a73fb99..3629e8bb989 100644 --- a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp +++ b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp @@ -72,34 +72,6 @@ nav_2d_msgs::msg::Twist2D twist3Dto2D(const geometry_msgs::msg::Twist & cmd_vel) return cmd_vel_2d; } - -geometry_msgs::msg::PoseStamped poseToPoseStamped( - const geometry_msgs::msg::Pose & pose_in, - const std::string & frame, const rclcpp::Time & stamp) -{ - geometry_msgs::msg::PoseStamped pose; - pose.header.frame_id = frame; - pose.header.stamp = stamp; - pose.pose = pose_in; - return pose; -} - -nav_msgs::msg::Path posesToPath(const std::vector & poses) -{ - nav_msgs::msg::Path path; - if (poses.empty()) { - return path; - } - path.poses.resize(poses.size()); - path.header.frame_id = poses[0].header.frame_id; - path.header.stamp = poses[0].header.stamp; - for (unsigned int i = 0; i < poses.size(); i++) { - path.poses[i] = poses[i]; - } - return path; -} - - nav_msgs::msg::Path posesToPath( const std::vector & poses, const std::string & frame, const rclcpp::Time & stamp) diff --git a/nav2_dwb_controller/nav_2d_utils/src/tf_help.cpp b/nav2_dwb_controller/nav_2d_utils/src/tf_help.cpp deleted file mode 100644 index 0916cc6a402..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/src/tf_help.cpp +++ /dev/null @@ -1,98 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2017, Locus Robotics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#include -#include -#include "nav_2d_utils/tf_help.hpp" - -namespace nav_2d_utils -{ - -bool transformPose( - const std::shared_ptr tf, - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose, - rclcpp::Duration & transform_tolerance -) -{ - if (in_pose.header.frame_id == frame) { - out_pose = in_pose; - return true; - } - - try { - tf->transform(in_pose, out_pose, frame); - return true; - } catch (tf2::ExtrapolationException & ex) { - auto transform = tf->lookupTransform( - frame, - in_pose.header.frame_id, - tf2::TimePointZero - ); - if ( - (rclcpp::Time(in_pose.header.stamp) - rclcpp::Time(transform.header.stamp)) > - transform_tolerance) - { - RCLCPP_ERROR( - rclcpp::get_logger("tf_help"), - "Transform data too old when converting from %s to %s", - in_pose.header.frame_id.c_str(), - frame.c_str() - ); - RCLCPP_ERROR( - rclcpp::get_logger("tf_help"), - "Data time: %ds %uns, Transform time: %ds %uns", - in_pose.header.stamp.sec, - in_pose.header.stamp.nanosec, - transform.header.stamp.sec, - transform.header.stamp.nanosec - ); - return false; - } else { - tf2::doTransform(in_pose, out_pose, transform); - return true; - } - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR( - rclcpp::get_logger("tf_help"), - "Exception in transformPose: %s", - ex.what() - ); - return false; - } - return false; -} - -} // namespace nav_2d_utils diff --git a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp index c7f5c502f76..fd7d209d3d7 100644 --- a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp +++ b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp @@ -48,59 +48,55 @@ using nav_2d_utils::posesToPath; TEST(nav_2d_utils, PosesToPathEmpty) { - std::vector poses; - nav_msgs::msg::Path path = posesToPath(poses); + std::vector poses; + auto node = std::make_shared("twod_utils_test_node"); + rclcpp::Time time = node->now(); + std::string frame = "test_frame"; + + nav_msgs::msg::Path path = posesToPath(poses, frame, time); EXPECT_EQ(path.poses.size(), 0ul); + EXPECT_EQ(path.header.frame_id, frame); + EXPECT_EQ(path.header.stamp, time); } TEST(nav_2d_utils, PosesToPathNonEmpty) { - std::vector poses; - geometry_msgs::msg::PoseStamped pose1; - rclcpp::Time time1, time2; auto node = std::make_shared("twod_utils_test_node"); - time1 = node->now(); + rclcpp::Time time = node->now(); + std::string frame = "map"; tf2::Quaternion quat1, quat2; quat1.setRPY(0, 0, 0.123); - pose1.pose.position.x = 1.0; - pose1.pose.position.y = 2.0; - pose1.pose.orientation.w = quat1.w(); - pose1.pose.orientation.x = quat1.x(); - pose1.pose.orientation.y = quat1.y(); - pose1.pose.orientation.z = quat1.z(); - pose1.header.stamp = time1; - pose1.header.frame_id = "frame1_id"; - - geometry_msgs::msg::PoseStamped pose2; - pose2.pose.position.x = 4.0; - pose2.pose.position.y = 5.0; quat2.setRPY(0, 0, 0.987); - pose2.pose.orientation.w = quat2.w(); - pose2.pose.orientation.x = quat2.x(); - pose2.pose.orientation.y = quat2.y(); - pose2.pose.orientation.z = quat2.z(); - time2 = node->now(); - pose2.header.stamp = time2; - pose2.header.frame_id = "frame2_id"; + geometry_msgs::msg::Pose pose1; + pose1.position.x = 1.0; + pose1.position.y = 2.0; + pose1.orientation = tf2::toMsg(quat1); - poses.push_back(pose1); - poses.push_back(pose2); + geometry_msgs::msg::Pose pose2; + pose2.position.x = 4.0; + pose2.position.y = 5.0; + pose2.orientation = tf2::toMsg(quat2); - nav_msgs::msg::Path path = posesToPath(poses); + std::vector poses = {pose1, pose2}; + + nav_msgs::msg::Path path = posesToPath(poses, frame, time); EXPECT_EQ(path.poses.size(), 2ul); EXPECT_EQ(path.poses[0].pose.position.x, 1.0); EXPECT_EQ(path.poses[0].pose.position.y, 2.0); - EXPECT_EQ(path.poses[0].header.stamp, time1); - EXPECT_EQ(path.poses[0].header.frame_id, "frame1_id"); EXPECT_EQ(path.poses[1].pose.position.x, 4.0); EXPECT_EQ(path.poses[1].pose.position.y, 5.0); - EXPECT_EQ(path.poses[1].header.frame_id, "frame2_id"); - EXPECT_EQ(path.header.stamp, time1); + for (const auto & stamped_pose : path.poses) { + EXPECT_EQ(stamped_pose.header.frame_id, frame); + EXPECT_EQ(stamped_pose.header.stamp, time); + } + + EXPECT_EQ(path.header.frame_id, frame); + EXPECT_EQ(path.header.stamp, time); } diff --git a/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt b/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt index f0cf339a322..fd861291fca 100644 --- a/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt +++ b/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt @@ -11,6 +11,3 @@ target_include_directories(2d_utils_tests ament_add_gtest(path_ops_tests path_ops_test.cpp) target_link_libraries(path_ops_tests path_ops) - -ament_add_gtest(tf_help_tests tf_help_test.cpp) -target_link_libraries(tf_help_tests tf_help conversions) diff --git a/nav2_dwb_controller/nav_2d_utils/test/tf_help_test.cpp b/nav2_dwb_controller/nav_2d_utils/test/tf_help_test.cpp deleted file mode 100644 index 4095567473a..00000000000 --- a/nav2_dwb_controller/nav_2d_utils/test/tf_help_test.cpp +++ /dev/null @@ -1,98 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2018, Wilco Bonestroo - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - */ - -#include -#include - -#include "gtest/gtest.h" -#include "nav_2d_utils/tf_help.hpp" - -TEST(TF_Help, TransformToSelf) { - bool result; - - std::shared_ptr tf; - std::string frame = "frame_id"; - geometry_msgs::msg::PoseStamped in_pose; - in_pose.header.frame_id = "frame_id"; - in_pose.pose.position.x = 1.0; - in_pose.pose.position.y = 2.0; - in_pose.pose.position.z = 3.0; - tf2::Quaternion qt; - qt.setRPY(0.5, 1.0, 1.5); - in_pose.pose.orientation.w = qt.w(); - in_pose.pose.orientation.x = qt.x(); - in_pose.pose.orientation.y = qt.y(); - in_pose.pose.orientation.z = qt.z(); - - geometry_msgs::msg::PoseStamped out_pose; - rclcpp::Duration transform_tolerance(0, 500); - - result = nav_2d_utils::transformPose(tf, frame, in_pose, out_pose, transform_tolerance); - - EXPECT_TRUE(result); - EXPECT_EQ(out_pose.header.frame_id, "frame_id"); - EXPECT_EQ(out_pose.pose.position.x, 1.0); - EXPECT_EQ(out_pose.pose.position.y, 2.0); - EXPECT_EQ(out_pose.pose.position.z, 3.0); - EXPECT_EQ(out_pose.pose.orientation.w, qt.w()); - EXPECT_EQ(out_pose.pose.orientation.x, qt.x()); - EXPECT_EQ(out_pose.pose.orientation.y, qt.y()); - EXPECT_EQ(out_pose.pose.orientation.z, qt.z()); -} - -TEST(TF_Help, EmptyBuffer) { - auto clock = std::make_shared(RCL_ROS_TIME); - auto buffer = std::make_shared(clock); - - std::string frame = "frame_id"; - geometry_msgs::msg::PoseStamped in_pose; - in_pose.header.frame_id = "other_frame_id"; - in_pose.pose.position.x = 1.0; - in_pose.pose.position.y = 2.0; - in_pose.pose.position.z = 3.0; - tf2::Quaternion qt; - qt.setRPY(0.5, 1.0, 1.5); - in_pose.pose.orientation.w = qt.w(); - in_pose.pose.orientation.x = qt.x(); - in_pose.pose.orientation.y = qt.y(); - in_pose.pose.orientation.z = qt.z(); - - geometry_msgs::msg::PoseStamped out_pose; - rclcpp::Duration transform_tolerance(0, 500); - - bool result; - result = nav_2d_utils::transformPose(buffer, frame, in_pose, out_pose, transform_tolerance); - - EXPECT_FALSE(result); -} diff --git a/nav2_graceful_controller/CMakeLists.txt b/nav2_graceful_controller/CMakeLists.txt index fc8859860b3..d9720ca6401 100644 --- a/nav2_graceful_controller/CMakeLists.txt +++ b/nav2_graceful_controller/CMakeLists.txt @@ -9,7 +9,6 @@ find_package(nav2_common REQUIRED) find_package(nav2_core REQUIRED) find_package(nav2_costmap_2d REQUIRED) find_package(nav2_util REQUIRED) -find_package(nav_2d_utils REQUIRED) find_package(nav_msgs REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) @@ -58,7 +57,6 @@ target_link_libraries(${library_name} PUBLIC nav2_ros_common::nav2_ros_common nav2_util::nav2_util_core nav2_costmap_2d::nav2_costmap_2d_core - nav_2d_utils::tf_help ${nav_msgs_TARGETS} pluginlib::pluginlib rclcpp::rclcpp @@ -104,7 +102,6 @@ ament_export_dependencies( nav2_core nav2_util nav2_costmap_2d - nav_2d_utils nav_msgs pluginlib rclcpp diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/path_handler.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/path_handler.hpp index aaa64f1bb62..a24a84c2228 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/path_handler.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/path_handler.hpp @@ -35,7 +35,7 @@ class PathHandler * @brief Constructor for nav2_graceful_controller::PathHandler */ PathHandler( - tf2::Duration transform_tolerance, + double transform_tolerance, std::shared_ptr tf, std::shared_ptr costmap_ros); @@ -71,7 +71,7 @@ class PathHandler nav_msgs::msg::Path getPlan() {return global_plan_;} protected: - rclcpp::Duration transform_tolerance_{0, 0}; + double transform_tolerance_{0}; std::shared_ptr tf_buffer_; std::shared_ptr costmap_ros_; nav_msgs::msg::Path global_plan_; diff --git a/nav2_graceful_controller/package.xml b/nav2_graceful_controller/package.xml index f162f3f0ed3..98b6e1e257a 100644 --- a/nav2_graceful_controller/package.xml +++ b/nav2_graceful_controller/package.xml @@ -16,7 +16,6 @@ nav2_core nav2_costmap_2d nav2_util - nav_2d_utils nav_msgs pluginlib rclcpp diff --git a/nav2_graceful_controller/src/graceful_controller.cpp b/nav2_graceful_controller/src/graceful_controller.cpp index fb0010698f4..0706c86378d 100644 --- a/nav2_graceful_controller/src/graceful_controller.cpp +++ b/nav2_graceful_controller/src/graceful_controller.cpp @@ -48,7 +48,7 @@ void GracefulController::configure( // Handles global path transformations path_handler_ = std::make_unique( - tf2::durationFromSec(params_->transform_tolerance), tf_buffer_, costmap_ros_); + params_->transform_tolerance, tf_buffer_, costmap_ros_); // Handles the control law to generate the velocity commands control_law_ = std::make_unique( diff --git a/nav2_graceful_controller/src/path_handler.cpp b/nav2_graceful_controller/src/path_handler.cpp index 9dbfc291f8d..b60b4a874f0 100644 --- a/nav2_graceful_controller/src/path_handler.cpp +++ b/nav2_graceful_controller/src/path_handler.cpp @@ -22,7 +22,7 @@ #include "nav2_core/controller_exceptions.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav_2d_utils/tf_help.hpp" +#include "nav2_util/robot_utils.hpp" #include "nav2_graceful_controller/path_handler.hpp" namespace nav2_graceful_controller @@ -31,7 +31,7 @@ namespace nav2_graceful_controller using nav2_util::geometry_utils::euclidean_distance; PathHandler::PathHandler( - tf2::Duration transform_tolerance, + double transform_tolerance, std::shared_ptr tf, std::shared_ptr costmap_ros) : transform_tolerance_(transform_tolerance), tf_buffer_(tf), costmap_ros_(costmap_ros) @@ -49,8 +49,8 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan( // Let's get the pose of the robot in the frame of the plan geometry_msgs::msg::PoseStamped robot_pose; - if (!nav_2d_utils::transformPose( - tf_buffer_, global_plan_.header.frame_id, pose, robot_pose, + if (!nav2_util::transformPoseInTargetFrame( + pose, robot_pose, *tf_buffer_, global_plan_.header.frame_id, transform_tolerance_)) { throw nav2_core::ControllerTFError("Unable to transform robot pose into global plan's frame"); @@ -88,9 +88,9 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan( stamped_pose.header.frame_id = global_plan_.header.frame_id; stamped_pose.header.stamp = robot_pose.header.stamp; stamped_pose.pose = global_plan_pose.pose; - if (!nav_2d_utils::transformPose( - tf_buffer_, costmap_ros_->getBaseFrameID(), stamped_pose, - transformed_pose, transform_tolerance_)) + if (!nav2_util::transformPoseInTargetFrame( + stamped_pose, transformed_pose, *tf_buffer_, + costmap_ros_->getBaseFrameID(), transform_tolerance_)) { throw nav2_core::ControllerTFError("Unable to transform plan pose into local frame"); } diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp index 544a98467d9..4233c91ef28 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp @@ -98,17 +98,6 @@ class PathHandler geometry_msgs::msg::PoseStamped getTransformedGoal(const builtin_interfaces::msg::Time & stamp); protected: - /** - * @brief Transform a pose to another frame - * @param frame Frame to transform to - * @param in_pose Input pose - * @param out_pose Output pose - * @return Bool if successful - */ - bool transformPose( - const std::string & frame, const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose) const; - /** * @brief Get largest dimension of costmap (radially) * @return Max distance from center of costmap to edge diff --git a/nav2_mppi_controller/src/path_handler.cpp b/nav2_mppi_controller/src/path_handler.cpp index 93593982c5c..55931f6bc62 100644 --- a/nav2_mppi_controller/src/path_handler.cpp +++ b/nav2_mppi_controller/src/path_handler.cpp @@ -17,6 +17,7 @@ #include "nav2_mppi_controller/tools/path_handler.hpp" #include "nav2_mppi_controller/tools/utils.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include "nav2_util/robot_utils.hpp" namespace mppi { @@ -85,7 +86,8 @@ PathHandler::getGlobalPlanConsideringBoundsInCostmapFrame( geometry_msgs::msg::PoseStamped costmap_plan_pose; global_plan_pose->header.stamp = global_pose.header.stamp; global_plan_pose->header.frame_id = global_plan_.header.frame_id; - transformPose(costmap_->getGlobalFrameID(), *global_plan_pose, costmap_plan_pose); + nav2_util::transformPoseInTargetFrame(*global_plan_pose, costmap_plan_pose, *tf_buffer_, + costmap_->getGlobalFrameID(), transform_tolerance_); // Check if pose is inside the costmap if (!costmap_->getCostmap()->worldToMap( @@ -109,7 +111,9 @@ geometry_msgs::msg::PoseStamped PathHandler::transformToGlobalPlanFrame( } geometry_msgs::msg::PoseStamped robot_pose; - if (!transformPose(global_plan_up_to_inversion_.header.frame_id, pose, robot_pose)) { + if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_buffer_, + global_plan_up_to_inversion_.header.frame_id, transform_tolerance_)) + { throw nav2_core::ControllerTFError( "Unable to transform robot pose into global plan's frame"); } @@ -142,27 +146,6 @@ nav_msgs::msg::Path PathHandler::transformPath( return transformed_plan; } -bool PathHandler::transformPose( - const std::string & frame, const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose) const -{ - if (in_pose.header.frame_id == frame) { - out_pose = in_pose; - return true; - } - - try { - tf_buffer_->transform( - in_pose, out_pose, frame, - tf2::durationFromSec(transform_tolerance_)); - out_pose.header.frame_id = frame; - return true; - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(logger_, "Exception in transformPose: %s", ex.what()); - } - return false; -} - double PathHandler::getMaxCostmapDist() { const auto & costmap = costmap_->getCostmap(); @@ -196,7 +179,9 @@ geometry_msgs::msg::PoseStamped PathHandler::getTransformedGoal( throw nav2_core::ControllerTFError("Goal pose has an empty frame_id"); } geometry_msgs::msg::PoseStamped transformed_goal; - if (!transformPose(costmap_->getGlobalFrameID(), goal, transformed_goal)) { + if (!nav2_util::transformPoseInTargetFrame(goal, transformed_goal, *tf_buffer_, + costmap_->getGlobalFrameID(), transform_tolerance_)) + { throw nav2_core::ControllerTFError("Unable to transform goal pose into costmap frame"); } return transformed_goal; diff --git a/nav2_mppi_controller/test/path_handler_test.cpp b/nav2_mppi_controller/test/path_handler_test.cpp index eb0bd140c43..e0f17e48411 100644 --- a/nav2_mppi_controller/test/path_handler_test.cpp +++ b/nav2_mppi_controller/test/path_handler_test.cpp @@ -46,13 +46,6 @@ class PathHandlerWrapper : public PathHandler return getGlobalPlanConsideringBoundsInCostmapFrame(pose); } - bool transformPoseWrapper( - const std::string & frame, const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose) const - { - return transformPose(frame, in_pose, out_pose); - } - geometry_msgs::msg::PoseStamped transformToGlobalPlanFrameWrapper( const geometry_msgs::msg::PoseStamped & pose) { @@ -180,12 +173,10 @@ TEST(PathHandlerTests, TestTransforms) path.poses[i].header.frame_id = "map"; } - geometry_msgs::msg::PoseStamped robot_pose, output_pose; + geometry_msgs::msg::PoseStamped robot_pose; robot_pose.header.frame_id = "odom"; robot_pose.pose.position.x = 2.5; - EXPECT_TRUE(handler.transformPoseWrapper("map", robot_pose, output_pose)); - EXPECT_EQ(output_pose.pose.position.x, 2.5); EXPECT_THROW(handler.transformToGlobalPlanFrameWrapper(robot_pose), std::runtime_error); handler.setPath(path); diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp index cc8b7915330..135a304dc26 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp @@ -43,7 +43,7 @@ class PathHandler * @brief Constructor for nav2_regulated_pure_pursuit_controller::PathHandler */ PathHandler( - tf2::Duration transform_tolerance, + double transform_tolerance, std::shared_ptr tf, std::shared_ptr costmap_ros); @@ -65,18 +65,6 @@ class PathHandler const geometry_msgs::msg::PoseStamped & pose, double max_robot_pose_search_dist, bool reject_unit_path = false); - /** - * @brief Transform a pose to another frame. - * @param frame Frame ID to transform to - * @param in_pose Pose input to transform - * @param out_pose transformed output - * @return bool if successful - */ - bool transformPose( - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose) const; - void setPlan(const nav_msgs::msg::Path & path) {global_plan_ = path;} nav_msgs::msg::Path getPlan() {return global_plan_;} @@ -89,7 +77,7 @@ class PathHandler double getCostmapMaxExtent() const; rclcpp::Logger logger_ {rclcpp::get_logger("RPPPathHandler")}; - tf2::Duration transform_tolerance_; + double transform_tolerance_; std::shared_ptr tf_; std::shared_ptr costmap_ros_; nav_msgs::msg::Path global_plan_; diff --git a/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp b/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp index 1fcc39b7e37..c91bb8dc8f7 100644 --- a/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp @@ -23,6 +23,7 @@ #include "nav2_core/controller_exceptions.hpp" #include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" +#include "nav2_util/robot_utils.hpp" namespace nav2_regulated_pure_pursuit_controller { @@ -30,7 +31,7 @@ namespace nav2_regulated_pure_pursuit_controller using nav2_util::geometry_utils::euclidean_distance; PathHandler::PathHandler( - tf2::Duration transform_tolerance, + double transform_tolerance, std::shared_ptr tf, std::shared_ptr costmap_ros) : transform_tolerance_(transform_tolerance), tf_(tf), costmap_ros_(costmap_ros) @@ -60,7 +61,9 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan( // let's get the pose of the robot in the frame of the plan geometry_msgs::msg::PoseStamped robot_pose; - if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) { + if (!nav2_util::transformPoseInTargetFrame(pose, robot_pose, *tf_, global_plan_.header.frame_id, + transform_tolerance_)) + { throw nav2_core::ControllerTFError("Unable to transform robot pose into global plan's frame"); } @@ -101,7 +104,9 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan( stamped_pose.header.frame_id = global_plan_.header.frame_id; stamped_pose.header.stamp = robot_pose.header.stamp; stamped_pose.pose = global_plan_pose.pose; - if (!transformPose(costmap_ros_->getBaseFrameID(), stamped_pose, transformed_pose)) { + if (!nav2_util::transformPoseInTargetFrame(stamped_pose, transformed_pose, *tf_, + costmap_ros_->getBaseFrameID(), transform_tolerance_)) + { throw nav2_core::ControllerTFError("Unable to transform plan pose into local frame"); } transformed_pose.pose.position.z = 0.0; @@ -128,24 +133,4 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan( return transformed_plan; } -bool PathHandler::transformPose( - const std::string frame, - const geometry_msgs::msg::PoseStamped & in_pose, - geometry_msgs::msg::PoseStamped & out_pose) const -{ - if (in_pose.header.frame_id == frame) { - out_pose = in_pose; - return true; - } - - try { - tf_->transform(in_pose, out_pose, frame, transform_tolerance_); - out_pose.header.frame_id = frame; - return true; - } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(logger_, "Exception in transformPose: %s", ex.what()); - } - return false; -} - } // namespace nav2_regulated_pure_pursuit_controller diff --git a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp index d8153ea16bd..1bd12ae3a06 100644 --- a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp @@ -61,7 +61,7 @@ void RegulatedPurePursuitController::configure( // Handles global path transformations path_handler_ = std::make_unique( - tf2::durationFromSec(params_->transform_tolerance), tf_, costmap_ros_); + params_->transform_tolerance, tf_, costmap_ros_); // Checks for imminent collisions collision_checker_ = std::make_unique(node, costmap_ros_, params_); diff --git a/nav2_smoother/CMakeLists.txt b/nav2_smoother/CMakeLists.txt index 465cadd670d..5831d10189c 100644 --- a/nav2_smoother/CMakeLists.txt +++ b/nav2_smoother/CMakeLists.txt @@ -9,7 +9,6 @@ find_package(nav2_core REQUIRED) find_package(nav2_costmap_2d REQUIRED) find_package(nav2_msgs REQUIRED) find_package(nav2_util REQUIRED) -find_package(nav_2d_utils REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) @@ -45,8 +44,6 @@ target_link_libraries(${library_name} PUBLIC nav2_ros_common::nav2_ros_common ) target_link_libraries(${library_name} PRIVATE - nav_2d_utils::conversions - nav_2d_utils::tf_help rclcpp_components::component tf2::tf2 ) diff --git a/nav2_smoother/package.xml b/nav2_smoother/package.xml index c2983d916ce..339bdeb5586 100644 --- a/nav2_smoother/package.xml +++ b/nav2_smoother/package.xml @@ -17,7 +17,6 @@ nav2_costmap_2d nav2_msgs nav2_util - nav_2d_utils pluginlib rclcpp rclcpp_components diff --git a/nav2_smoother/src/nav2_smoother.cpp b/nav2_smoother/src/nav2_smoother.cpp index eb852c1eb52..66e3fd926ff 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -23,8 +23,6 @@ #include "nav2_core/smoother_exceptions.hpp" #include "nav2_smoother/nav2_smoother.hpp" #include "nav2_ros_common/node_utils.hpp" -#include "nav_2d_utils/conversions.hpp" -#include "nav_2d_utils/tf_help.hpp" #include "tf2_ros/create_timer_ros.hpp" using namespace std::chrono_literals; diff --git a/nav2_util/src/robot_utils.cpp b/nav2_util/src/robot_utils.cpp index 912d73d0859..d333df9cf14 100644 --- a/nav2_util/src/robot_utils.cpp +++ b/nav2_util/src/robot_utils.cpp @@ -50,6 +50,11 @@ bool transformPoseInTargetFrame( { static rclcpp::Logger logger = rclcpp::get_logger("transformPoseInTargetFrame"); + if(input_pose.header.frame_id == target_frame) { + transformed_pose = input_pose; + return true; + } + try { transformed_pose = tf_buffer.transform( input_pose, target_frame,