Skip to content
This repository has been archived by the owner on Mar 19, 2024. It is now read-only.

Commit

Permalink
Fix: adjust for changed heartbeat::Publisher API.
Browse files Browse the repository at this point in the history
  • Loading branch information
aentinger committed Jun 28, 2023
1 parent c087463 commit 380a72b
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 3 deletions.
3 changes: 1 addition & 2 deletions include/ros2_cyphal_bridge/Node.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include <std_msgs/msg/u_int64.hpp>
#include <std_msgs/msg/u_int16_multi_array.hpp>

#include <ros2_heartbeat/Publisher.h>
#include <ros2_heartbeat/publisher/Publisher.h>
#include <ros2_loop_rate_monitor/Monitor.h>

#include "CanManager.h"
Expand Down Expand Up @@ -62,7 +62,6 @@ class Node : public rclcpp::Node

std::chrono::steady_clock::time_point const _node_start;

static std::chrono::milliseconds constexpr HEARTBEAT_LOOP_RATE{100};
heartbeat::Publisher::SharedPtr _heartbeat_pub;
void init_heartbeat();

Expand Down
2 changes: 1 addition & 1 deletion src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ void Node::init_heartbeat()
std::stringstream heartbeat_topic;
heartbeat_topic << "/l3xz/" << get_name() << "/heartbeat";

_heartbeat_pub = heartbeat::Publisher::create(*this, heartbeat_topic.str(), HEARTBEAT_LOOP_RATE);
_heartbeat_pub = heartbeat::Publisher::create(*this, heartbeat_topic.str());
}

void Node::init_cyphal_heartbeat()
Expand Down

0 comments on commit 380a72b

Please sign in to comment.