Common
common packages for kyubic
 
Loading...
Searching...
No Matches
rtc_time.hpp
Go to the documentation of this file.
1
10#ifndef _RTC_TIME_HPP
11#define _RTC_TIME_HPP
12
13#include <cstdint>
14#include <driver_msgs/msg/rtc_time.hpp>
15#include <memory>
16#include <mutex>
17#include <proto_files/conversion_driver_msgs__RtcTime.hpp>
18#include <protolink/client.hpp>
19#include <rclcpp/rclcpp.hpp>
20#include <timer/timeout.hpp>
21
23{
24
28class RtcTime : public rclcpp::Node
29{
30public:
31 explicit RtcTime(const rclcpp::NodeOptions & options);
32
33private:
34 uint16_t sub_port;
35 uint64_t timeout_ms;
36
37 protolink::IoContext io_context_;
38 std::shared_ptr<protolink::udp_protocol::soket> sock_;
39 std::shared_ptr<timer::Timeout> timeout_;
40 std::mutex mutex_;
41
42 using ProtoRtcTime = protolink__driver_msgs__RtcTime::driver_msgs__RtcTime;
43 std::shared_ptr<protolink::udp_protocol::Subscriber<ProtoRtcTime>> protolink_subscriber_;
44
45 rclcpp::Publisher<driver_msgs::msg::RtcTime>::SharedPtr pub_;
46 rclcpp::TimerBase::SharedPtr timer_;
47
48 void protolink_callback(const ProtoRtcTime & _msg);
49};
50
51} // namespace driver::sensors_esp32_driver
52
53#endif
RTC Time class.
Definition: rtc_time.hpp:29
driver for sensors_esp32
timeout library