Skip to content

Commit

Permalink
Fix windows warnings
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <emerson.b.knapp@gmail.com>
  • Loading branch information
emersonknapp committed Jul 6, 2023
1 parent 1f4896a commit 4bf4b32
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions topic_tools/include/topic_tools/drop_node.hpp
Expand Up @@ -35,8 +35,8 @@ class DropNode final : public ToolBaseNode
private:
void process_message(std::shared_ptr<rclcpp::SerializedMessage> msg) override;

int x_;
int y_;
int64_t x_;
int64_t y_;
int count_{0};
};
} // namespace topic_tools
Expand Down
4 changes: 2 additions & 2 deletions topic_tools/include/topic_tools/throttle_node.hpp
Expand Up @@ -29,7 +29,7 @@ namespace topic_tools
{
class ThrottleNode final : public ToolBaseNode
{
using Sent = std::pair<double, uint32_t>;
using Sent = std::pair<double, size_t>;

public:
TOPIC_TOOLS_PUBLIC
Expand All @@ -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_;
Expand Down
2 changes: 1 addition & 1 deletion topic_tools/test/test_topic_tool.hpp
Expand Up @@ -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_++;
Expand Down

0 comments on commit 4bf4b32

Please sign in to comment.