Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: const func & fix typos #9

Merged
merged 1 commit into from
Mar 4, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ class ManagedTransformBufferProvider
*/
std::optional<TransformStamped> lookupTransform(
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger);
const tf2::Duration & timeout, const rclcpp::Logger & logger) const;

/** @brief Traverse TF tree built by local TF listener.
*
Expand All @@ -185,7 +185,7 @@ class ManagedTransformBufferProvider
*/
TraverseResult traverseTree(
const std::string & target_frame, const std::string & source_frame,
const tf2::Duration & timeout, const rclcpp::Logger & logger);
const tf2::Duration & timeout, const rclcpp::Logger & logger) const;

/** @brief Get a dynamic transform from the TF buffer.
*
Expand All @@ -198,7 +198,7 @@ class ManagedTransformBufferProvider
*/
std::optional<TransformStamped> getDynamicTransform(
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger);
const tf2::Duration & timeout, const rclcpp::Logger & logger) const;

/** @brief Get a static transform from local TF buffer.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ std::optional<TransformStamped> ManagedTransformBuffer::getTransform<TransformSt
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger)
{
provider_->getTransform(target_frame, source_frame, time, timeout, logger);
return provider_->getTransform(target_frame, source_frame, time, timeout, logger);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,12 @@ ManagedTransformBufferProvider & ManagedTransformBufferProvider::getInstance(
if (instance.isStatic()) {
instance.registerAsDynamic();
}
if (clock_type != instance.clock_->get_clock_type()) {
RCLCPP_WARN_THROTTLE(
instance.logger_, *instance.clock_, 3000,
"Input clock type does not match (%d vs. %d). Input clock type will be ignored.",
clock_type, instance.clock_->get_clock_type());
}
}
if (clock_type != instance.clock_->get_clock_type()) {
RCLCPP_WARN_THROTTLE(
instance.logger_, *instance.clock_, 3000,
"Input clock type does not match (%d vs. %d). Input clock type will be ignored.", clock_type,
instance.clock_->get_clock_type());
}
return instance;
}
Expand Down Expand Up @@ -191,10 +191,9 @@ void ManagedTransformBufferProvider::tfCallback(

std::optional<TransformStamped> ManagedTransformBufferProvider::lookupTransform(
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger)
const tf2::Duration & timeout, const rclcpp::Logger & logger) const
{
try {
auto x = node_->get_logger();
auto tf = tf_buffer_->lookupTransform(target_frame, source_frame, time, timeout);
return std::make_optional<TransformStamped>(tf);
} catch (const tf2::TransformException & ex) {
Expand All @@ -207,7 +206,7 @@ std::optional<TransformStamped> ManagedTransformBufferProvider::lookupTransform(

TraverseResult ManagedTransformBufferProvider::traverseTree(
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ readability-function-cognitive-complexity ⚠️
function traverseTree has cognitive complexity of 34 (threshold 25)

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

Expand Down Expand Up @@ -285,7 +284,7 @@ TraverseResult ManagedTransformBufferProvider::traverseTree(

std::optional<TransformStamped> ManagedTransformBufferProvider::getDynamicTransform(
const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time,
const tf2::Duration & timeout, const rclcpp::Logger & logger)
const tf2::Duration & timeout, const rclcpp::Logger & logger) const
{
return lookupTransform(target_frame, source_frame, time, timeout, logger);
}
Expand Down
Loading