diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp index c4400327013..baac1dbfea8 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp @@ -38,14 +38,14 @@ class Circle : public Polygon * @param polygon_name Name of circle * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing */ Circle( const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance); + const tf2::Duration & transform_timeout); /** * @brief Circle class destructor */ diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp index 7791265179f..51aae97e9f9 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp @@ -99,18 +99,18 @@ class CollisionDetector : public nav2_util::LifecycleNode /** * @brief Supporting routine creating and configuring all polygons * @param base_frame_id Robot base frame ID - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @return True if all polygons were configured successfully or false in failure case */ bool configurePolygons( const std::string & base_frame_id, - const tf2::Duration & transform_tolerance); + const tf2::Duration & transform_timeout); /** * @brief Supporting routine creating and configuring all data sources * @param base_frame_id Robot base frame ID * @param odom_frame_id Odometry frame ID. Used as global frame to get * source->base time interpolated transform. - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -119,7 +119,7 @@ class CollisionDetector : public nav2_util::LifecycleNode bool configureSources( const std::string & base_frame_id, const std::string & odom_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp index 09a13658092..f1b13653fc7 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp @@ -118,18 +118,18 @@ class CollisionMonitor : public nav2_util::LifecycleNode /** * @brief Supporting routine creating and configuring all polygons * @param base_frame_id Robot base frame ID - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @return True if all polygons were configured successfully or false in failure case */ bool configurePolygons( const std::string & base_frame_id, - const tf2::Duration & transform_tolerance); + const tf2::Duration & transform_timeout); /** * @brief Supporting routine creating and configuring all data sources * @param base_frame_id Robot base frame ID * @param odom_frame_id Odometry frame ID. Used as global frame to get * source->base time interpolated transform. - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -138,7 +138,7 @@ class CollisionMonitor : public nav2_util::LifecycleNode bool configureSources( const std::string & base_frame_id, const std::string & odom_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp index bfe8d09ed33..d248ff2f340 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp @@ -39,7 +39,7 @@ class PointCloud : public Source * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID. The output data will be transformed into this frame. * @param global_frame_id Global frame ID for correct transform calculation - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -50,7 +50,7 @@ class PointCloud : public Source const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); /** diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp index 815694d83c6..d9f032235e4 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp @@ -47,14 +47,14 @@ class Polygon * @param polygon_name Name of polygon * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID - * @param transform_tolerance Transform tolerance + * @param transform_timeout how long to block before failing */ Polygon( const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance); + const tf2::Duration & transform_timeout); /** * @brief Polygon destructor */ @@ -248,8 +248,8 @@ class Polygon std::shared_ptr tf_buffer_; /// @brief Base frame ID std::string base_frame_id_; - /// @brief Transform tolerance - tf2::Duration transform_tolerance_; + /// @brief Transform timeout on how long to block before failing + tf2::Duration transform_timeout_; // Visualization /// @brief Whether to publish the polygon diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp index 1dc15195f6e..6de75411f95 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp @@ -39,7 +39,7 @@ class Range : public Source * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID. The output data will be transformed into this frame. * @param global_frame_id Global frame ID for correct transform calculation - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -50,7 +50,7 @@ class Range : public Source const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); /** diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp index efaf82e0e37..4aeea01f0cf 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp @@ -39,7 +39,7 @@ class Scan : public Source * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID. The output data will be transformed into this frame. * @param global_frame_id Global frame ID for correct transform calculation - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -50,7 +50,7 @@ class Scan : public Source const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); /** diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp index 865a3c023b9..499e86d3c5a 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp @@ -44,7 +44,7 @@ class Source * @param tf_buffer Shared pointer to a TF buffer * @param base_frame_id Robot base frame ID. The output data will be transformed into this frame. * @param global_frame_id Global frame ID for correct transform calculation - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param source_timeout Maximum time interval in which data is considered valid * @param base_shift_correction Whether to correct source data towards to base frame movement, * considering the difference between current time and latest source time @@ -55,7 +55,7 @@ class Source const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction); /** @@ -143,8 +143,8 @@ class Source std::string base_frame_id_; /// @brief Global frame ID for correct transform calculation std::string global_frame_id_; - /// @brief Transform tolerance - tf2::Duration transform_tolerance_; + /// @brief Transform timeout + tf2::Duration transform_timeout_; /// @brief Maximum time interval in which data is considered valid rclcpp::Duration source_timeout_; /// @brief Whether to correct source data towards to base frame movement, diff --git a/nav2_collision_monitor/params/collision_detector_params.yaml b/nav2_collision_monitor/params/collision_detector_params.yaml index 68b4cd7b507..4da026b5431 100644 --- a/nav2_collision_monitor/params/collision_detector_params.yaml +++ b/nav2_collision_monitor/params/collision_detector_params.yaml @@ -3,7 +3,7 @@ collision_detector: frequency: 10.0 base_frame_id: "base_footprint" odom_frame_id: "odom" - transform_tolerance: 0.5 + transform_timeout: 0.5 source_timeout: 5.0 base_shift_correction: True polygons: ["PolygonFront"] diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml index fcb01f54829..158b98bc769 100644 --- a/nav2_collision_monitor/params/collision_monitor_params.yaml +++ b/nav2_collision_monitor/params/collision_monitor_params.yaml @@ -5,7 +5,7 @@ collision_monitor: cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" state_topic: "collision_monitor_state" - transform_tolerance: 0.5 + transform_timeout: 0.5 source_timeout: 5.0 base_shift_correction: True stop_pub_timeout: 2.0 diff --git a/nav2_collision_monitor/src/circle.cpp b/nav2_collision_monitor/src/circle.cpp index fa0fc33a4f8..169b578b0c8 100644 --- a/nav2_collision_monitor/src/circle.cpp +++ b/nav2_collision_monitor/src/circle.cpp @@ -28,8 +28,8 @@ Circle::Circle( const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) -: Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance) + const tf2::Duration & transform_timeout) +: Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_timeout) { RCLCPP_INFO(logger_, "[%s]: Creating Circle", polygon_name_.c_str()); } diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index b6c871c540f..f9d6cbdd99e 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -141,7 +141,7 @@ CollisionDetector::on_shutdown(const rclcpp_lifecycle::State & /*state*/) bool CollisionDetector::getParameters() { std::string base_frame_id, odom_frame_id; - tf2::Duration transform_tolerance; + tf2::Duration transform_timeout; rclcpp::Duration source_timeout(2.0, 0.0); auto node = shared_from_this(); @@ -156,9 +156,9 @@ bool CollisionDetector::getParameters() node, "odom_frame_id", rclcpp::ParameterValue("odom")); odom_frame_id = get_parameter("odom_frame_id").as_string(); nav2_util::declare_parameter_if_not_declared( - node, "transform_tolerance", rclcpp::ParameterValue(0.1)); - transform_tolerance = - tf2::durationFromSec(get_parameter("transform_tolerance").as_double()); + node, "transform_timeout", rclcpp::ParameterValue(0.1)); + transform_timeout = + tf2::durationFromSec(get_parameter("transform_timeout").as_double()); nav2_util::declare_parameter_if_not_declared( node, "source_timeout", rclcpp::ParameterValue(2.0)); source_timeout = @@ -168,12 +168,12 @@ bool CollisionDetector::getParameters() const bool base_shift_correction = get_parameter("base_shift_correction").as_bool(); - if (!configurePolygons(base_frame_id, transform_tolerance)) { + if (!configurePolygons(base_frame_id, transform_timeout)) { return false; } if (!configureSources( - base_frame_id, odom_frame_id, transform_tolerance, source_timeout, + base_frame_id, odom_frame_id, transform_timeout, source_timeout, base_shift_correction)) { return false; @@ -184,7 +184,7 @@ bool CollisionDetector::getParameters() bool CollisionDetector::configurePolygons( const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) + const tf2::Duration & transform_timeout) { try { auto node = shared_from_this(); @@ -202,11 +202,11 @@ bool CollisionDetector::configurePolygons( if (polygon_type == "polygon") { polygons_.push_back( std::make_shared( - node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance)); + node, polygon_name, tf_buffer_, base_frame_id, transform_timeout)); } else if (polygon_type == "circle") { polygons_.push_back( std::make_shared( - node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance)); + node, polygon_name, tf_buffer_, base_frame_id, transform_timeout)); } else { // Error if something else RCLCPP_ERROR( get_logger(), @@ -242,7 +242,7 @@ bool CollisionDetector::configurePolygons( bool CollisionDetector::configureSources( const std::string & base_frame_id, const std::string & odom_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) { @@ -262,7 +262,7 @@ bool CollisionDetector::configureSources( if (source_type == "scan") { std::shared_ptr s = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); s->configure(); @@ -270,7 +270,7 @@ bool CollisionDetector::configureSources( } else if (source_type == "pointcloud") { std::shared_ptr p = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); p->configure(); @@ -278,7 +278,7 @@ bool CollisionDetector::configureSources( } else if (source_type == "range") { std::shared_ptr r = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); r->configure(); diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 29e3f3031de..8489c2eadce 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -220,7 +220,7 @@ bool CollisionMonitor::getParameters( std::string & state_topic) { std::string base_frame_id, odom_frame_id; - tf2::Duration transform_tolerance; + tf2::Duration transform_timeout; rclcpp::Duration source_timeout(2.0, 0.0); auto node = shared_from_this(); @@ -242,9 +242,9 @@ bool CollisionMonitor::getParameters( node, "odom_frame_id", rclcpp::ParameterValue("odom")); odom_frame_id = get_parameter("odom_frame_id").as_string(); nav2_util::declare_parameter_if_not_declared( - node, "transform_tolerance", rclcpp::ParameterValue(0.1)); - transform_tolerance = - tf2::durationFromSec(get_parameter("transform_tolerance").as_double()); + node, "transform_timeout", rclcpp::ParameterValue(0.1)); + transform_timeout = + tf2::durationFromSec(get_parameter("transform_timeout").as_double()); nav2_util::declare_parameter_if_not_declared( node, "source_timeout", rclcpp::ParameterValue(2.0)); source_timeout = @@ -259,13 +259,13 @@ bool CollisionMonitor::getParameters( stop_pub_timeout_ = rclcpp::Duration::from_seconds(get_parameter("stop_pub_timeout").as_double()); - if (!configurePolygons(base_frame_id, transform_tolerance)) { + if (!configurePolygons(base_frame_id, transform_timeout)) { return false; } if ( !configureSources( - base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction)) + base_frame_id, odom_frame_id, transform_timeout, source_timeout, base_shift_correction)) { return false; } @@ -275,7 +275,7 @@ bool CollisionMonitor::getParameters( bool CollisionMonitor::configurePolygons( const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) + const tf2::Duration & transform_timeout) { try { auto node = shared_from_this(); @@ -293,11 +293,11 @@ bool CollisionMonitor::configurePolygons( if (polygon_type == "polygon") { polygons_.push_back( std::make_shared( - node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance)); + node, polygon_name, tf_buffer_, base_frame_id, transform_timeout)); } else if (polygon_type == "circle") { polygons_.push_back( std::make_shared( - node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance)); + node, polygon_name, tf_buffer_, base_frame_id, transform_timeout)); } else { // Error if something else RCLCPP_ERROR( get_logger(), @@ -322,7 +322,7 @@ bool CollisionMonitor::configurePolygons( bool CollisionMonitor::configureSources( const std::string & base_frame_id, const std::string & odom_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) { @@ -342,7 +342,7 @@ bool CollisionMonitor::configureSources( if (source_type == "scan") { std::shared_ptr s = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); s->configure(); @@ -350,7 +350,7 @@ bool CollisionMonitor::configureSources( } else if (source_type == "pointcloud") { std::shared_ptr p = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); p->configure(); @@ -358,7 +358,7 @@ bool CollisionMonitor::configureSources( } else if (source_type == "range") { std::shared_ptr r = std::make_shared( node, source_name, tf_buffer_, base_frame_id, odom_frame_id, - transform_tolerance, source_timeout, base_shift_correction); + transform_timeout, source_timeout, base_shift_correction); r->configure(); diff --git a/nav2_collision_monitor/src/pointcloud.cpp b/nav2_collision_monitor/src/pointcloud.cpp index fb3fca201d0..2a285e1abac 100644 --- a/nav2_collision_monitor/src/pointcloud.cpp +++ b/nav2_collision_monitor/src/pointcloud.cpp @@ -15,6 +15,7 @@ #include "nav2_collision_monitor/pointcloud.hpp" #include +#include #include "sensor_msgs/point_cloud2_iterator.hpp" @@ -30,12 +31,12 @@ PointCloud::PointCloud( const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) : Source( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, source_timeout, base_shift_correction), + transform_timeout, source_timeout, base_shift_correction), data_(nullptr) { RCLCPP_INFO(logger_, "[%s]: Creating PointCloud", source_name_.c_str()); @@ -78,30 +79,25 @@ bool PointCloud::getData( return false; } - tf2::Transform tf_transform; - if (base_shift_correction_) { - // Obtaining the transform to get data from source frame and time where it was received - // to the base frame and current time - if ( - !nav2_util::getTransform( - data_->header.frame_id, data_->header.stamp, - base_frame_id_, curr_time, global_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } else { - // Obtaining the transform to get data from source frame to base frame without time shift - // considered. Less accurate but much more faster option not dependent on state estimation - // frames. - if ( - !nav2_util::getTransform( - data_->header.frame_id, base_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } + const auto tf_transform = [&]() -> std::optional { + // Obtaining the transform to get data from source frame and time where it was received to the + // base frame and current time + if (base_shift_correction_) { + return nav2_util::getTransform( + base_frame_id_, curr_time, data_->header.frame_id, + data_->header.stamp, global_frame_id_, transform_timeout_, + tf_buffer_); + } + + // Obtaining the transform to get data from source frame to base frame without time shift + // considered. Less accurate but much more faster option not dependent on state estimation + // frames. + return nav2_util::getTransform( + base_frame_id_, data_->header.frame_id, transform_timeout_, + tf_buffer_); + }(); + + if (!tf_transform.has_value()) {return false;} sensor_msgs::PointCloud2ConstIterator iter_x(*data_, "x"); sensor_msgs::PointCloud2ConstIterator iter_y(*data_, "y"); @@ -111,7 +107,7 @@ bool PointCloud::getData( for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) { // Transform point coordinates from source frame -> to base frame tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Refill data array if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) { diff --git a/nav2_collision_monitor/src/polygon.cpp b/nav2_collision_monitor/src/polygon.cpp index 248bdcec6de..a5d145cc683 100644 --- a/nav2_collision_monitor/src/polygon.cpp +++ b/nav2_collision_monitor/src/polygon.cpp @@ -15,6 +15,7 @@ #include "nav2_collision_monitor/polygon.hpp" #include +#include #include #include "geometry_msgs/msg/point.hpp" @@ -33,11 +34,11 @@ Polygon::Polygon( const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) + const tf2::Duration & transform_timeout) : node_(node), polygon_name_(polygon_name), action_type_(DO_NOTHING), slowdown_ratio_(0.0), linear_limit_(0.0), angular_limit_(0.0), footprint_sub_(nullptr), tf_buffer_(tf_buffer), - base_frame_id_(base_frame_id), transform_tolerance_(transform_tolerance) + base_frame_id_(base_frame_id), transform_timeout_(transform_timeout) { RCLCPP_INFO(logger_, "[%s]: Creating Polygon", polygon_name_.c_str()); } @@ -82,7 +83,7 @@ bool Polygon::configure() polygon_name_.c_str(), footprint_topic.c_str()); footprint_sub_ = std::make_unique( node, footprint_topic, *tf_buffer_, - base_frame_id_, tf2::durationToSec(transform_tolerance_)); + base_frame_id_, tf2::durationToSec(transform_timeout_)); } if (visualize_) { @@ -203,21 +204,20 @@ void Polygon::updatePolygon() std::size_t new_size = polygon_.polygon.points.size(); // Get the transform from PolygonStamped frame to base_frame_id_ - tf2::Transform tf_transform; - if ( - !nav2_util::getTransform( - polygon_.header.frame_id, base_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return; - } + std::optional tf_transform = nav2_util::getTransform( + base_frame_id_, + polygon_.header.frame_id, + transform_timeout_, + tf_buffer_); + + if (!tf_transform.has_value()) {return;} // Correct main poly_ vertices poly_.resize(new_size); for (std::size_t i = 0; i < new_size; i++) { // Transform point coordinates from PolygonStamped frame -> to base frame tf2::Vector3 p_v3_s(polygon_.polygon.points[i].x, polygon_.polygon.points[i].y, 0.0); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Fill poly_ array poly_[i] = {p_v3_b.x(), p_v3_b.y()}; @@ -476,21 +476,20 @@ void Polygon::updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr m } // Get the transform from PolygonStamped frame to base_frame_id_ - tf2::Transform tf_transform; - if ( - !nav2_util::getTransform( - msg->header.frame_id, base_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return; - } + std::optional tf_transform = nav2_util::getTransform( + base_frame_id_, + msg->header.frame_id, + transform_timeout_, + tf_buffer_); + + if (!tf_transform.has_value()) {return;} // Set main poly_ vertices first time poly_.resize(new_size); for (std::size_t i = 0; i < new_size; i++) { // Transform point coordinates from PolygonStamped frame -> to base frame tf2::Vector3 p_v3_s(msg->polygon.points[i].x, msg->polygon.points[i].y, 0.0); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Fill poly_ array poly_[i] = {p_v3_b.x(), p_v3_b.y()}; diff --git a/nav2_collision_monitor/src/range.cpp b/nav2_collision_monitor/src/range.cpp index 45540a9c4d0..9a58812e247 100644 --- a/nav2_collision_monitor/src/range.cpp +++ b/nav2_collision_monitor/src/range.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include "nav2_util/node_utils.hpp" #include "nav2_util/robot_utils.hpp" @@ -30,12 +31,12 @@ Range::Range( const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) : Source( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, source_timeout, base_shift_correction), + transform_timeout, source_timeout, base_shift_correction), data_(nullptr) { RCLCPP_INFO(logger_, "[%s]: Creating Range", source_name_.c_str()); @@ -87,30 +88,26 @@ bool Range::getData( return false; } - tf2::Transform tf_transform; - if (base_shift_correction_) { - // Obtaining the transform to get data from source frame and time where it was received - // to the base frame and current time - if ( - !nav2_util::getTransform( - data_->header.frame_id, data_->header.stamp, - base_frame_id_, curr_time, global_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } else { - // Obtaining the transform to get data from source frame to base frame without time shift - // considered. Less accurate but much more faster option not dependent on state estimation - // frames. - if ( - !nav2_util::getTransform( - data_->header.frame_id, base_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } + const auto tf_transform = [&]() -> std::optional { + // Obtaining the transform to get data from source frame and time where it was received to the + // base frame and current time + if (base_shift_correction_) { + return nav2_util::getTransform( + base_frame_id_, curr_time, data_->header.frame_id, + data_->header.stamp, global_frame_id_, transform_timeout_, + tf_buffer_); + } + + // Obtaining the transform to get data from source frame to base frame without time shift + // considered. Less accurate but much more faster option not dependent on state estimation + // frames. + return nav2_util::getTransform( + base_frame_id_, data_->header.frame_id, transform_timeout_, + tf_buffer_); + }(); + + if (!tf_transform.has_value()) {return false;} + // Calculate poses and refill data array float angle; @@ -124,7 +121,7 @@ bool Range::getData( data_->range * std::cos(angle), data_->range * std::sin(angle), 0.0); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Refill data array data.push_back({p_v3_b.x(), p_v3_b.y()}); @@ -138,7 +135,7 @@ bool Range::getData( data_->range * std::cos(angle), data_->range * std::sin(angle), 0.0); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Refill data array data.push_back({p_v3_b.x(), p_v3_b.y()}); diff --git a/nav2_collision_monitor/src/scan.cpp b/nav2_collision_monitor/src/scan.cpp index 45f1e62d701..edd8c941a5b 100644 --- a/nav2_collision_monitor/src/scan.cpp +++ b/nav2_collision_monitor/src/scan.cpp @@ -16,6 +16,7 @@ #include #include +#include #include "nav2_util/robot_utils.hpp" @@ -28,12 +29,12 @@ Scan::Scan( const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) : Source( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, source_timeout, base_shift_correction), + transform_timeout, source_timeout, base_shift_correction), data_(nullptr) { RCLCPP_INFO(logger_, "[%s]: Creating Scan", source_name_.c_str()); @@ -77,30 +78,25 @@ bool Scan::getData( return false; } - tf2::Transform tf_transform; - if (base_shift_correction_) { - // Obtaining the transform to get data from source frame and time where it was received - // to the base frame and current time - if ( - !nav2_util::getTransform( - data_->header.frame_id, data_->header.stamp, - base_frame_id_, curr_time, global_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } else { - // Obtaining the transform to get data from source frame to base frame without time shift - // considered. Less accurate but much more faster option not dependent on state estimation - // frames. - if ( - !nav2_util::getTransform( - data_->header.frame_id, base_frame_id_, - transform_tolerance_, tf_buffer_, tf_transform)) - { - return false; - } - } + const auto tf_transform = [&]() -> std::optional { + // Obtaining the transform to get data from source frame and time where it was received to the + // base frame and current time + if (base_shift_correction_) { + return nav2_util::getTransform( + base_frame_id_, curr_time, data_->header.frame_id, + data_->header.stamp, global_frame_id_, transform_timeout_, + tf_buffer_); + } + + // Obtaining the transform to get data from source frame to base frame without time shift + // considered. Less accurate but much more faster option not dependent on state estimation + // frames. + return nav2_util::getTransform( + base_frame_id_, data_->header.frame_id, transform_timeout_, + tf_buffer_); + }(); + + if (!tf_transform.has_value()) {return false;} // Calculate poses and refill data array float angle = data_->angle_min; @@ -111,7 +107,7 @@ bool Scan::getData( data_->ranges[i] * std::cos(angle), data_->ranges[i] * std::sin(angle), 0.0); - tf2::Vector3 p_v3_b = tf_transform * p_v3_s; + tf2::Vector3 p_v3_b = tf_transform.value() * p_v3_s; // Refill data array data.push_back({p_v3_b.x(), p_v3_b.y()}); diff --git a/nav2_collision_monitor/src/source.cpp b/nav2_collision_monitor/src/source.cpp index a27876f05b3..f14fc17bb99 100644 --- a/nav2_collision_monitor/src/source.cpp +++ b/nav2_collision_monitor/src/source.cpp @@ -29,12 +29,12 @@ Source::Source( const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & source_timeout, const bool base_shift_correction) : node_(node), source_name_(source_name), tf_buffer_(tf_buffer), base_frame_id_(base_frame_id), global_frame_id_(global_frame_id), - transform_tolerance_(transform_tolerance), source_timeout_(source_timeout), + transform_timeout_(transform_timeout), source_timeout_(source_timeout), base_shift_correction_(base_shift_correction) { } diff --git a/nav2_collision_monitor/test/collision_detector_node_test.cpp b/nav2_collision_monitor/test/collision_detector_node_test.cpp index b0b926fde05..5f0e27f6cf0 100644 --- a/nav2_collision_monitor/test/collision_detector_node_test.cpp +++ b/nav2_collision_monitor/test/collision_detector_node_test.cpp @@ -53,7 +53,7 @@ static const char STATE_TOPIC[]{"collision_detector_state"}; static const char COLLISION_POINTS_MARKERS_TOPIC[]{"/collision_detector/collision_points_marker"}; static const int MIN_POINTS{1}; static const double SIMULATION_TIME_STEP{0.01}; -static const double TRANSFORM_TOLERANCE{0.5}; +static const double TRANSFORM_TIMEOUT{0.5}; static const double SOURCE_TIMEOUT{5.0}; static const double FREQUENCY{10.0}; @@ -246,9 +246,9 @@ void Tester::setCommonParameters() rclcpp::Parameter("odom_frame_id", ODOM_FRAME_ID)); cd_->declare_parameter( - "transform_tolerance", rclcpp::ParameterValue(TRANSFORM_TOLERANCE)); + "transform_timeout", rclcpp::ParameterValue(TRANSFORM_TIMEOUT)); cd_->set_parameter( - rclcpp::Parameter("transform_tolerance", TRANSFORM_TOLERANCE)); + rclcpp::Parameter("transform_timeout", TRANSFORM_TIMEOUT)); cd_->declare_parameter( "source_timeout", rclcpp::ParameterValue(SOURCE_TIMEOUT)); cd_->set_parameter( diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index 94801a3d2a3..17a26e3e580 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -60,7 +60,7 @@ static const double LINEAR_LIMIT{0.4}; static const double ANGULAR_LIMIT{0.09}; static const double TIME_BEFORE_COLLISION{1.0}; static const double SIMULATION_TIME_STEP{0.01}; -static const double TRANSFORM_TOLERANCE{0.5}; +static const double TRANSFORM_TIMEOUT{0.5}; static const double SOURCE_TIMEOUT{5.0}; static const double STOP_PUB_TIMEOUT{0.1}; @@ -276,9 +276,9 @@ void Tester::setCommonParameters() rclcpp::Parameter("odom_frame_id", ODOM_FRAME_ID)); cm_->declare_parameter( - "transform_tolerance", rclcpp::ParameterValue(TRANSFORM_TOLERANCE)); + "transform_timeout", rclcpp::ParameterValue(TRANSFORM_TIMEOUT)); cm_->set_parameter( - rclcpp::Parameter("transform_tolerance", TRANSFORM_TOLERANCE)); + rclcpp::Parameter("transform_timeout", TRANSFORM_TIMEOUT)); cm_->declare_parameter( "source_timeout", rclcpp::ParameterValue(SOURCE_TIMEOUT)); cm_->set_parameter( diff --git a/nav2_collision_monitor/test/polygons_test.cpp b/nav2_collision_monitor/test/polygons_test.cpp index 2ab46cdcede..0239d5f2cec 100644 --- a/nav2_collision_monitor/test/polygons_test.cpp +++ b/nav2_collision_monitor/test/polygons_test.cpp @@ -57,7 +57,7 @@ static const double LINEAR_LIMIT{0.4}; static const double ANGULAR_LIMIT{0.09}; static const double TIME_BEFORE_COLLISION{1.0}; static const double SIMULATION_TIME_STEP{0.01}; -static const tf2::Duration TRANSFORM_TOLERANCE{tf2::durationFromSec(0.1)}; +static const tf2::Duration TRANSFORM_TIMEOUT{tf2::durationFromSec(0.1)}; class TestNode : public nav2_util::LifecycleNode { @@ -160,9 +160,9 @@ class PolygonWrapper : public nav2_collision_monitor::Polygon const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) + const tf2::Duration & transform_timeout) : nav2_collision_monitor::Polygon( - node, polygon_name, tf_buffer, base_frame_id, transform_tolerance) + node, polygon_name, tf_buffer, base_frame_id, transform_timeout) { } @@ -185,9 +185,9 @@ class CircleWrapper : public nav2_collision_monitor::Circle const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, - const tf2::Duration & transform_tolerance) + const tf2::Duration & transform_timeout) : nav2_collision_monitor::Circle( - node, polygon_name, tf_buffer, base_frame_id, transform_tolerance) + node, polygon_name, tf_buffer, base_frame_id, transform_timeout) { } @@ -364,7 +364,7 @@ void Tester::createPolygon(const std::string & action_type, const bool is_static polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_TRUE(polygon_->configure()); polygon_->activate(); } @@ -376,7 +376,7 @@ void Tester::createCircle(const std::string & action_type) circle_ = std::make_shared( test_node_, CIRCLE_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_TRUE(circle_->configure()); circle_->activate(); } @@ -521,7 +521,7 @@ TEST_F(Tester, testPolygonUndeclaredActionType) // "action_type" parameter is not initialized polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(polygon_->configure()); // Check that "action_type" parameter is not set after configuring ASSERT_TRUE(checkUndeclaredParameter(POLYGON_NAME, "action_type")); @@ -536,7 +536,7 @@ TEST_F(Tester, testPolygonUndeclaredPoints) rclcpp::Parameter(std::string(POLYGON_NAME) + ".action_type", "stop")); polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(polygon_->configure()); // Check that "points" and "polygon_sub_topic" parameters are not set after configuring ASSERT_TRUE(checkUndeclaredParameter(POLYGON_NAME, "points")); @@ -550,7 +550,7 @@ TEST_F(Tester, testPolygonIncorrectActionType) polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(polygon_->configure()); } @@ -567,7 +567,7 @@ TEST_F(Tester, testPolygonIncorrectPoints1) polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(polygon_->configure()); } @@ -584,7 +584,7 @@ TEST_F(Tester, testPolygonIncorrectPoints2) polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(polygon_->configure()); } @@ -602,7 +602,7 @@ TEST_F(Tester, testPolygonMaxPoints) polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_TRUE(polygon_->configure()); EXPECT_EQ(polygon_->getMinPoints(), max_points + 1); } @@ -613,7 +613,7 @@ TEST_F(Tester, testCircleUndeclaredRadius) circle_ = std::make_shared( test_node_, CIRCLE_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_FALSE(circle_->configure()); // Check that "radius" parameter is not set after configuring @@ -755,7 +755,7 @@ TEST_F(Tester, testPolygonGetPointsInsideEdge) polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_TRUE(polygon_->configure()); std::vector points; @@ -889,7 +889,7 @@ TEST_F(Tester, testPolygonDefaultVisualize) // Create new polygon polygon_ = std::make_shared( test_node_, POLYGON_NAME, - tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); + tf_buffer_, BASE_FRAME_ID, TRANSFORM_TIMEOUT); ASSERT_TRUE(polygon_->configure()); polygon_->activate(); diff --git a/nav2_collision_monitor/test/sources_test.cpp b/nav2_collision_monitor/test/sources_test.cpp index 0bfcd1a062c..6db76b27550 100644 --- a/nav2_collision_monitor/test/sources_test.cpp +++ b/nav2_collision_monitor/test/sources_test.cpp @@ -52,7 +52,7 @@ static const char POINTCLOUD_NAME[]{"PointCloud"}; static const char POINTCLOUD_TOPIC[]{"pointcloud"}; static const char RANGE_NAME[]{"Range"}; static const char RANGE_TOPIC[]{"range"}; -static const tf2::Duration TRANSFORM_TOLERANCE{tf2::durationFromSec(0.1)}; +static const tf2::Duration TRANSFORM_TIMEOUT{tf2::durationFromSec(0.1)}; static const rclcpp::Duration DATA_TIMEOUT{rclcpp::Duration::from_seconds(5.0)}; class TestNode : public nav2_util::LifecycleNode @@ -171,12 +171,12 @@ class ScanWrapper : public nav2_collision_monitor::Scan const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & data_timeout, const bool base_shift_correction) : nav2_collision_monitor::Scan( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, data_timeout, base_shift_correction) + transform_timeout, data_timeout, base_shift_correction) {} bool dataReceived() const @@ -194,12 +194,12 @@ class PointCloudWrapper : public nav2_collision_monitor::PointCloud const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & data_timeout, const bool base_shift_correction) : nav2_collision_monitor::PointCloud( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, data_timeout, base_shift_correction) + transform_timeout, data_timeout, base_shift_correction) {} bool dataReceived() const @@ -217,12 +217,12 @@ class RangeWrapper : public nav2_collision_monitor::Range const std::shared_ptr tf_buffer, const std::string & base_frame_id, const std::string & global_frame_id, - const tf2::Duration & transform_tolerance, + const tf2::Duration & transform_timeout, const rclcpp::Duration & data_timeout, const bool base_shift_correction) : nav2_collision_monitor::Range( node, source_name, tf_buffer, base_frame_id, global_frame_id, - transform_tolerance, data_timeout, base_shift_correction) + transform_timeout, data_timeout, base_shift_correction) {} bool dataReceived() const @@ -294,7 +294,7 @@ void Tester::createSources(const bool base_shift_correction) scan_ = std::make_shared( test_node_, SCAN_NAME, tf_buffer_, BASE_FRAME_ID, GLOBAL_FRAME_ID, - TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction); + TRANSFORM_TIMEOUT, DATA_TIMEOUT, base_shift_correction); scan_->configure(); // Create PointCloud object @@ -314,7 +314,7 @@ void Tester::createSources(const bool base_shift_correction) pointcloud_ = std::make_shared( test_node_, POINTCLOUD_NAME, tf_buffer_, BASE_FRAME_ID, GLOBAL_FRAME_ID, - TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction); + TRANSFORM_TIMEOUT, DATA_TIMEOUT, base_shift_correction); pointcloud_->configure(); // Create Range object @@ -329,7 +329,7 @@ void Tester::createSources(const bool base_shift_correction) range_ = std::make_shared( test_node_, RANGE_NAME, tf_buffer_, BASE_FRAME_ID, GLOBAL_FRAME_ID, - TRANSFORM_TOLERANCE, DATA_TIMEOUT, base_shift_correction); + TRANSFORM_TIMEOUT, DATA_TIMEOUT, base_shift_correction); range_->configure(); } diff --git a/nav2_util/include/nav2_util/robot_utils.hpp b/nav2_util/include/nav2_util/robot_utils.hpp index 20f09cbce66..9e3b8f6768b 100644 --- a/nav2_util/include/nav2_util/robot_utils.hpp +++ b/nav2_util/include/nav2_util/robot_utils.hpp @@ -17,8 +17,9 @@ #ifndef NAV2_UTIL__ROBOT_UTILS_HPP_ #define NAV2_UTIL__ROBOT_UTILS_HPP_ -#include #include +#include +#include #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/twist.hpp" @@ -26,7 +27,6 @@ #include "tf2/time.h" #include "tf2_ros/buffer.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "rclcpp/rclcpp.hpp" namespace nav2_util { @@ -62,35 +62,19 @@ bool transformPoseInTargetFrame( /** * @brief Obtains a transform from source_frame_id -> to target_frame_id - * @param source_frame_id Source frame ID to convert from * @param target_frame_id Target frame ID to convert to - * @param transform_tolerance Transform tolerance - * @param tf_buffer TF buffer to use for the transformation - * @param tf_transform Output source->target transform - * @return True if got correct transform, otherwise false - */ -bool getTransform( - const std::string & source_frame_id, - const std::string & target_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - tf2::Transform & tf2_transform); - -/** - * @brief Obtains a transform from source_frame_id -> to target_frame_id * @param source_frame_id Source frame ID to convert from - * @param target_frame_id Target frame ID to convert to - * @param transform_tolerance Transform tolerance + * @param transform_timeout How long to block before failing * @param tf_buffer TF buffer to use for the transformation - * @param transform_msg Output source->target transform - * @return True if got correct transform, otherwise false + * @return transform Output source->target transform */ -bool getTransform( - const std::string & source_frame_id, +template +[[nodiscard]] std::optional getTransform( const std::string & target_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - geometry_msgs::msg::TransformStamped & transform_msg); + const std::string & source_frame_id, + const tf2::Duration & transform_timeout, + const std::shared_ptr tf_buffer); + /** * @brief Obtains a transform from source_frame_id at source_time -> diff --git a/nav2_util/src/robot_utils.cpp b/nav2_util/src/robot_utils.cpp index 93b5ef6bc70..22f9800f002 100644 --- a/nav2_util/src/robot_utils.cpp +++ b/nav2_util/src/robot_utils.cpp @@ -14,6 +14,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -77,99 +78,104 @@ bool transformPoseInTargetFrame( return false; } -bool getTransform( - const std::string & source_frame_id, +template<> +std::optional getTransform( const std::string & target_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - geometry_msgs::msg::TransformStamped & transform_msg) + const std::string & source_frame_id, + const tf2::Duration & transform_timeout, + const std::shared_ptr tf_buffer) { - if (source_frame_id == target_frame_id) { - // We are already in required frame - return true; - } - try { // Obtaining the transform to get data from source to target frame - transform_msg = tf_buffer->lookupTransform( + return tf_buffer->lookupTransform( target_frame_id, source_frame_id, - tf2::TimePointZero, transform_tolerance); + tf2::TimePointZero, transform_timeout); } catch (tf2::TransformException & e) { RCLCPP_ERROR( rclcpp::get_logger("getTransform"), "Failed to get \"%s\"->\"%s\" frame transform: %s", source_frame_id.c_str(), target_frame_id.c_str(), e.what()); - return false; + return std::nullopt; } - return true; } -bool getTransform( - const std::string & source_frame_id, +template<> +std::optional getTransform( const std::string & target_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - tf2::Transform & tf2_transform) -{ - tf2_transform.setIdentity(); // initialize by identical transform - geometry_msgs::msg::TransformStamped transform; - if (getTransform(source_frame_id, target_frame_id, transform_tolerance, tf_buffer, transform)) { - // Convert TransformStamped to TF2 transform - tf2::fromMsg(transform.transform, tf2_transform); - return true; - } - return false; -} - -bool getTransform( + const rclcpp::Time & target_time, const std::string & source_frame_id, const rclcpp::Time & source_time, - const std::string & target_frame_id, - const rclcpp::Time & target_time, const std::string & fixed_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - geometry_msgs::msg::TransformStamped & transform_msg) + const tf2::Duration & transform_timeout, + const std::shared_ptr tf_buffer) { try { // Obtaining the transform to get data from source to target frame. // This also considers the time shift between source and target. - transform_msg = tf_buffer->lookupTransform( + return tf_buffer->lookupTransform( target_frame_id, target_time, source_frame_id, source_time, - fixed_frame_id, transform_tolerance); + fixed_frame_id, transform_timeout); } catch (tf2::TransformException & ex) { RCLCPP_ERROR( rclcpp::get_logger("getTransform"), "Failed to get \"%s\"->\"%s\" frame transform: %s", source_frame_id.c_str(), target_frame_id.c_str(), ex.what()); - return false; + return std::nullopt; } - - return true; } -bool getTransform( +template<> +std::optional getTransform( + const std::string & target_frame_id, const std::string & source_frame_id, - const rclcpp::Time & source_time, + const tf2::Duration & transform_timeout, + const std::shared_ptr tf_buffer) +{ + tf2::Transform tf2_transform; + tf2_transform.setIdentity(); // initialize by identical transform + + if (source_frame_id == target_frame_id) { + // We are already in required frame + return tf2_transform; + } + + const auto transform_msg = getTransform( + target_frame_id, + source_frame_id, + transform_timeout, + tf_buffer); + + if (!transform_msg.has_value()) {return std::nullopt;} + tf2::fromMsg(transform_msg.value().transform, tf2_transform); + return tf2_transform; +} + +template<> +std::optional getTransform( const std::string & target_frame_id, const rclcpp::Time & target_time, + const std::string & source_frame_id, + const rclcpp::Time & source_time, const std::string & fixed_frame_id, - const tf2::Duration & transform_tolerance, - const std::shared_ptr tf_buffer, - tf2::Transform & tf2_transform) + const tf2::Duration & transform_timeout, + const std::shared_ptr tf_buffer) { - geometry_msgs::msg::TransformStamped transform; - tf2_transform.setIdentity(); // initialize by identical transform - if (getTransform( - source_frame_id, source_time, target_frame_id, target_time, fixed_frame_id, - transform_tolerance, tf_buffer, transform)) - { - // Convert TransformStamped to TF2 transform - tf2::fromMsg(transform.transform, tf2_transform); - return true; - } - return false; + + const auto transform_msg = getTransform( + target_frame_id, + target_time, + source_frame_id, + source_time, + fixed_frame_id, + transform_timeout, + tf_buffer); + + if (!transform_msg.has_value()) {return std::nullopt;} + + tf2::Transform tf2_transform; + tf2::fromMsg(transform_msg.value().transform, tf2_transform); + return tf2_transform; } bool validateTwist(const geometry_msgs::msg::Twist & msg)