Skip to content

Commit 6029666

Browse files
authored
Merge pull request #189 from aica-technology/feat/tf-node
feat(components): use parent node for tf listener (cpp)
2 parents ccf3321 + fe31ea6 commit 6029666

File tree

4 files changed

+7
-6
lines changed

4 files changed

+7
-6
lines changed

CHANGELOG.md

+1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ Release Versions:
2121
## Upcoming changes
2222

2323
- feat: improve devcontainer configuration (#198)
24+
- feat: use parent node for tf listener (cpp) (#189)
2425

2526
## 5.1.0
2627

source/modulo_components/include/modulo_components/ComponentInterface.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -544,9 +544,9 @@ class ComponentInterface {
544544
const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
545545
const tf2::Duration& duration);
546546

547-
double rate_; ///< The component rate in Hz
548-
double period_; ///< The componet period in s
549-
std::mutex step_mutex_; ///< Mutex for step callback
547+
double rate_; ///< The component rate in Hz
548+
double period_; ///< The componet period in s
549+
std::mutex step_mutex_;///< Mutex for step callback
550550

551551
std::map<std::string, modulo_core::Predicate> predicates_;///< Map of predicates
552552
std::shared_ptr<rclcpp::Publisher<modulo_interfaces::msg::PredicateCollection>>

source/modulo_components/src/ComponentInterface.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -488,7 +488,8 @@ void ComponentInterface::add_tf_listener() {
488488
RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding TF buffer and listener.");
489489
console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
490490
this->tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->node_clock_->get_clock());
491-
this->tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*this->tf_buffer_);
491+
this->tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
492+
*this->tf_buffer_, this->node_base_, this->node_logging_, this->node_parameters_, this->node_topics_);
492493
} else {
493494
RCLCPP_DEBUG(this->node_logging_->get_logger(), "TF buffer and listener already exist.");
494495
}

source/modulo_components/test/cpp/test_component_communication.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,7 @@ TEST_F(ComponentCommunicationTest, TwistInputOutput) {
6464
auto twist = std::make_shared<geometry_msgs::msg::Twist>();
6565
twist->linear.x = 1.0;
6666
auto input_node = std::make_shared<MinimalTwistInput<Component>>(rclcpp::NodeOptions(), "/topic");
67-
auto output_node =
68-
std::make_shared<MinimalTwistOutput<Component>>(rclcpp::NodeOptions(), "/topic", twist, true);
67+
auto output_node = std::make_shared<MinimalTwistOutput<Component>>(rclcpp::NodeOptions(), "/topic", twist, true);
6968
this->exec_->add_node(input_node);
7069
this->exec_->add_node(output_node);
7170
auto return_code = this->exec_->spin_until_future_complete(input_node->received_future, 500ms);

0 commit comments

Comments
 (0)