Skip to content

Commit

Permalink
Fix mixed-up implementations in TfSubscription creation (moveit#1073)
Browse files Browse the repository at this point in the history
Co-authored-by: Jean-Christophe Ruel <jeanchristophe.ruel@elmec.ca>
  • Loading branch information
2 people authored and AndyZe committed Mar 15, 2022
1 parent c78aebe commit dc23186
Showing 1 changed file with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,15 +88,15 @@ bool CurrentStateMonitorMiddlewareHandle::sleepFor(const std::chrono::nanosecond
return rclcpp::sleep_for(nanoseconds);
}

void CurrentStateMonitorMiddlewareHandle::createStaticTfSubscription(TfCallback callback)
void CurrentStateMonitorMiddlewareHandle::createDynamicTfSubscription(TfCallback callback)
{
static_transform_subscriber_ =
transform_subscriber_ =
node_->create_subscription<tf2_msgs::msg::TFMessage>("/tf", tf2_ros::DynamicListenerQoS(), callback);
}

void CurrentStateMonitorMiddlewareHandle::createDynamicTfSubscription(TfCallback callback)
void CurrentStateMonitorMiddlewareHandle::createStaticTfSubscription(TfCallback callback)
{
transform_subscriber_ =
static_transform_subscriber_ =
node_->create_subscription<tf2_msgs::msg::TFMessage>("/tf_static", tf2_ros::StaticListenerQoS(), callback);
}

Expand Down

0 comments on commit dc23186

Please sign in to comment.