Common
common packages for kyubic
 
Loading...
Searching...
No Matches
depth.hpp
Go to the documentation of this file.
1
10#ifndef _DEPTH_HPP
11#define _DEPTH_HPP
12
13#include <cstdint>
14#include <driver_msgs/msg/depth.hpp>
15#include <proto_files/conversion_driver_msgs__BoolStamped.hpp>
16#include <proto_files/conversion_driver_msgs__Depth.hpp>
17#include <protolink/client.hpp>
18#include <rclcpp/rclcpp.hpp>
19#include <timer/timeout.hpp>
20
26{
27
31class Depth : public rclcpp::Node
32{
33public:
38 explicit Depth(const rclcpp::NodeOptions & options);
39
40private:
41 // Network settings
42 std::string mcu_ip_addr;
43 uint16_t mcu_port;
44 uint16_t this_port;
45 uint64_t timeout_ms;
46
47 protolink::IoContext io_context_;
48 std::shared_ptr<protolink::udp_protocol::soket> sock_;
49 std::shared_ptr<timer::Timeout> timeout_;
50 std::mutex mutex_;
51
52 using protoDepth = protolink__driver_msgs__Depth::driver_msgs__Depth;
53 using protoBoolStamped = protolink__driver_msgs__BoolStamped::driver_msgs__BoolStamped;
54 std::shared_ptr<protolink::udp_protocol::Publisher<protoBoolStamped>> protolink_publisher_;
55 std::shared_ptr<protolink::udp_protocol::Subscriber<protoDepth>> protolink_subscriber_;
56
57 rclcpp::Publisher<driver_msgs::msg::Depth>::SharedPtr pub_;
58 rclcpp::Subscription<driver_msgs::msg::BoolStamped>::SharedPtr sub_;
59 rclcpp::TimerBase::SharedPtr timer_;
60
61 void protolink_callback(const protoDepth & _msg);
62 void ros_callback(const driver_msgs::msg::BoolStamped & _msg);
63};
64
65} // namespace driver::sensors_esp32_driver
66
67#endif
Depth class.
Definition: depth.hpp:32
driver for sensors_esp32
timeout library