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>
31class Depth :
public rclcpp::Node
38 explicit Depth(
const rclcpp::NodeOptions & options);
42 std::string mcu_ip_addr;
47 protolink::IoContext io_context_;
48 std::shared_ptr<protolink::udp_protocol::soket> sock_;
49 std::shared_ptr<timer::Timeout> timeout_;
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_;
57 rclcpp::Publisher<driver_msgs::msg::Depth>::SharedPtr pub_;
58 rclcpp::Subscription<driver_msgs::msg::BoolStamped>::SharedPtr sub_;
59 rclcpp::TimerBase::SharedPtr timer_;
61 void protolink_callback(
const protoDepth & _msg);
62 void ros_callback(
const driver_msgs::msg::BoolStamped & _msg);
Depth class.
Definition: depth.hpp:32