diff --git a/fuse_core/src/fuse_echo.cpp b/fuse_core/src/fuse_echo.cpp index 4a1fd81f9..369e40bc3 100644 --- a/fuse_core/src/fuse_echo.cpp +++ b/fuse_core/src/fuse_echo.cpp @@ -50,8 +50,7 @@ namespace fuse_core class FuseEcho : public rclcpp::Node { public: - explicit FuseEcho(rclcpp::NodeOptions options): - Node("fuse_echo", options) + explicit FuseEcho(rclcpp::NodeOptions options): Node("fuse_echo", options) { // Subscribe to the constraint topic graph_subscriber_ = this->create_subscription( @@ -72,20 +71,20 @@ class FuseEcho : public rclcpp::Node rclcpp::Subscription::SharedPtr graph_subscriber_; rclcpp::Subscription::SharedPtr transaction_subscriber_; - void graphCallback(const fuse_msgs::msg::SerializedGraph::SharedPtr msg) + void graphCallback(const fuse_msgs::msg::SerializedGraph& msg) { std::cout << "-------------------------" << std::endl; std::cout << "GRAPH:" << std::endl; - std::cout << "received at: " << rclcpp::Clock().now().seconds() << std::endl; + std::cout << "received at: " << this->now().seconds() << std::endl; auto graph = graph_deserializer_.deserialize(msg); graph->print(); } - void transactionCallback(const fuse_msgs::msg::SerializedTransaction::SharedPtr msg) + void transactionCallback(const fuse_msgs::msg::SerializedTransaction& msg) { std::cout << "-------------------------" << std::endl; std::cout << "TRANSACTION:" << std::endl; - std::cout << "received at: " << rclcpp::Clock().now().seconds() << std::endl; + std::cout << "received at: " << this->now().seconds() << std::endl; auto transaction = transaction_deserializer_.deserialize(msg); transaction.print(); } @@ -103,4 +102,4 @@ int main(int argc, char **argv) } #include -RCLCPP_COMPONENTS_REGISTER_NODE(fuse_core::FuseEcho) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE(fuse_core::FuseEcho)