From 4bf4b32e703b70f15a198100a936c6ae20119185 Mon Sep 17 00:00:00 2001 From: Emerson Knapp Date: Thu, 6 Jul 2023 15:02:17 -0700 Subject: [PATCH] Fix windows warnings Signed-off-by: Emerson Knapp --- topic_tools/include/topic_tools/drop_node.hpp | 4 ++-- topic_tools/include/topic_tools/throttle_node.hpp | 4 ++-- topic_tools/test/test_topic_tool.hpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/topic_tools/include/topic_tools/drop_node.hpp b/topic_tools/include/topic_tools/drop_node.hpp index 726f988..f28d66f 100644 --- a/topic_tools/include/topic_tools/drop_node.hpp +++ b/topic_tools/include/topic_tools/drop_node.hpp @@ -35,8 +35,8 @@ class DropNode final : public ToolBaseNode private: void process_message(std::shared_ptr msg) override; - int x_; - int y_; + int64_t x_; + int64_t y_; int count_{0}; }; } // namespace topic_tools diff --git a/topic_tools/include/topic_tools/throttle_node.hpp b/topic_tools/include/topic_tools/throttle_node.hpp index bd1ec0a..ff4491a 100644 --- a/topic_tools/include/topic_tools/throttle_node.hpp +++ b/topic_tools/include/topic_tools/throttle_node.hpp @@ -29,7 +29,7 @@ namespace topic_tools { class ThrottleNode final : public ToolBaseNode { - using Sent = std::pair; + using Sent = std::pair; public: TOPIC_TOOLS_PUBLIC @@ -45,7 +45,7 @@ class ThrottleNode final : public ToolBaseNode } throttle_type_; double msgs_per_sec_; std::chrono::nanoseconds period_; - int bytes_per_sec_; + int64_t bytes_per_sec_; double window_; rclcpp::Time last_time_; bool use_wall_clock_; diff --git a/topic_tools/test/test_topic_tool.hpp b/topic_tools/test/test_topic_tool.hpp index 9c0f0b7..b5f2534 100644 --- a/topic_tools/test/test_topic_tool.hpp +++ b/topic_tools/test/test_topic_tool.hpp @@ -46,7 +46,7 @@ class TestTopicTool : public ::testing::Test } protected: - void topic_callback(const std_msgs::msg::String::SharedPtr msg) + void topic_callback(std_msgs::msg::String::ConstSharedPtr msg) { msg_validator_(msg); received_msgs_++;