Skip to content

Commit

Permalink
feat: remove unnecessary async calls
Browse files Browse the repository at this point in the history
Signed-off-by: Amadeusz Szymko <amadeusz.szymko.2@tier4.jp>
  • Loading branch information
amadeuszsz committed Mar 6, 2025
1 parent 367d8f2 commit ec1b5ea
Show file tree
Hide file tree
Showing 2 changed files with 45 additions and 65 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -181,13 +181,12 @@ class ManagedTransformBufferProvider
*
* @param[in] target_frame the frame to which data should be transformed
* @param[in] source_frame the frame where the data originated
* @param[in] timeout how long to block before failing
* @param[in] logger logger, if not specified, default logger will be used
* @return a traverse result indicating if the transform is possible and if it is static
*/
TraverseResult traverseTree(
const std::string & target_frame, const std::string & source_frame,
const tf2::Duration & timeout, const rclcpp::Logger & logger);
const rclcpp::Logger & logger);

/** @brief Get a dynamic transform from the TF buffer.
*
Expand Down
107 changes: 44 additions & 63 deletions managed_transform_buffer/src/managed_transform_buffer_provider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@

#include <algorithm>
#include <cstdint>
#include <future>
#include <memory>
#include <string>
#include <utility>
Expand Down Expand Up @@ -217,11 +216,8 @@ std::optional<TransformStamped> ManagedTransformBufferProvider::lookupTransform(
}

TraverseResult ManagedTransformBufferProvider::traverseTree(
const std::string & target_frame, const std::string & source_frame, const tf2::Duration & timeout,
const rclcpp::Logger & logger)
const std::string & target_frame, const std::string & source_frame, const rclcpp::Logger & logger)
{
std::atomic<bool> timeout_reached{false};

auto framesToRoot = [this](
const std::string & start_frame, const TreeMap & tf_tree,
std::vector<std::string> & frames_out,
Expand All @@ -244,55 +240,42 @@ TraverseResult ManagedTransformBufferProvider::traverseTree(
return true;
};

auto traverse = [this, &timeout_reached, &framesToRoot](
const std::string & t1, const std::string & t2,
const rclcpp::Logger & logger) -> TraverseResult {
while (!timeout_reached.load()) {
std::vector<std::string> frames_from_t1;
std::vector<std::string> frames_from_t2;
std::shared_lock<std::shared_mutex> sh_tree_lock(tree_mutex_);
auto last_tf_tree = *tf_tree_;
sh_tree_lock.unlock();

// Collect all frames from bottom to the top of TF tree for both frames
if (
!framesToRoot(t1, last_tf_tree, frames_from_t1, logger) ||
!framesToRoot(t2, last_tf_tree, frames_from_t2, logger)) {
// Possibly TF loop occurred
return {false, false};
}
std::vector<std::string> frames_from_t1;
std::vector<std::string> frames_from_t2;
std::shared_lock<std::shared_mutex> sh_tree_lock(tree_mutex_);
auto last_tf_tree = *tf_tree_;
sh_tree_lock.unlock();

// Collect all frames from bottom to the top of TF tree for both frames
if (
!framesToRoot(target_frame, last_tf_tree, frames_from_t1, logger) ||
!framesToRoot(source_frame, last_tf_tree, frames_from_t2, logger)) {
// Possibly TF loop occurred
return {false, false};
}

// Find common ancestor
bool only_static_requested_from_t1 = true;
bool only_static_requested_from_t2 = true;
for (auto & frame_from_t1 : frames_from_t1) {
auto frame_from_t1_it = last_tf_tree.find(frame_from_t1);
if (frame_from_t1_it != last_tf_tree.end()) { // Otherwise frame is TF root (no parent)
only_static_requested_from_t1 &= last_tf_tree.at(frame_from_t1).is_static;
}
for (auto & frame_from_t2 : frames_from_t2) {
auto frame_from_t2_it = last_tf_tree.find(frame_from_t2);
if (frame_from_t2_it != last_tf_tree.end()) { // Otherwise frame is TF root (no parent)
only_static_requested_from_t2 &= last_tf_tree.at(frame_from_t2).is_static;
}
if (frame_from_t1 == frame_from_t2) {
return {true, only_static_requested_from_t1 && only_static_requested_from_t2};
}
}
only_static_requested_from_t1 = true;
only_static_requested_from_t2 = true;
// Find common ancestor
bool only_static_requested_from_t1 = true;
bool only_static_requested_from_t2 = true;
for (auto & frame_from_t1 : frames_from_t1) {
auto frame_from_t1_it = last_tf_tree.find(frame_from_t1);
if (frame_from_t1_it != last_tf_tree.end()) { // Otherwise frame is TF root (no parent)
only_static_requested_from_t1 &= last_tf_tree.at(frame_from_t1).is_static;
}
for (auto & frame_from_t2 : frames_from_t2) {
auto frame_from_t2_it = last_tf_tree.find(frame_from_t2);
if (frame_from_t2_it != last_tf_tree.end()) { // Otherwise frame is TF root (no parent)
only_static_requested_from_t2 &= last_tf_tree.at(frame_from_t2).is_static;
}
if (frame_from_t1 == frame_from_t2) {
return {true, only_static_requested_from_t1 && only_static_requested_from_t2};
}
}
// Timeout reached
return {false, false};
};

std::future<TraverseResult> future =
std::async(std::launch::async, traverse, target_frame, source_frame, logger);
if (future.wait_for(timeout) == std::future_status::ready) {
return future.get();
only_static_requested_from_t1 = true;
only_static_requested_from_t2 = true;
}
timeout_reached.store(true);

// No common ancestor found
return {false, false};
}

Expand Down Expand Up @@ -358,22 +341,20 @@ std::optional<TransformStamped> ManagedTransformBufferProvider::getUnknownTransf
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger)
{
// Initialize local TF listener and base TF listener
// Initialize TF listener
activateListener();

// Check local TF tree and TF buffer asynchronously
// Check TF buffer
auto discovery_timeout = std::max(timeout, discovery_timeout_);
std::future<TraverseResult> traverse_future = std::async(
std::launch::async, &ManagedTransformBufferProvider::traverseTree, this, target_frame,
source_frame, discovery_timeout, logger);
std::future<std::optional<TransformStamped>> tf_future = std::async(
std::launch::async, &ManagedTransformBufferProvider::lookupTransform, this, target_frame,
source_frame, time, discovery_timeout, logger);
auto traverse_result = traverse_future.get();
auto tf = tf_future.get();

// Mimic lookup transform error if TF not exists in tree or buffer
if (!traverse_result.success || !tf.has_value()) {
auto tf = lookupTransform(target_frame, source_frame, time, discovery_timeout, logger);
if (!tf.has_value()) {
deactivateListener();
return std::nullopt;
}

// Check whether TF is static
auto traverse_result = traverseTree(target_frame, source_frame, logger);
if (!traverse_result.success) {
deactivateListener();
return std::nullopt;
}
Expand Down

0 comments on commit ec1b5ea

Please sign in to comment.