modbus_MediaPipe/test.cpp

25 lines
1.1 KiB
C++
Raw Permalink Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

// rclcpp 是 ROS2 的 C++ 客戶端函式庫ROS Client Library for C++
// 提供 Node、Publisher/Subscriber、Timer、Logging 等 API。
#include "rclcpp/rclcpp.hpp"
// std_msgs/msg/string.hpp 是 ROS2 內建的訊息型別套件 std_msgs 裡的 String 訊息定義。
// 這個訊息就只有一個欄位std::string data;
#include "std_msgs/msg/string.hpp"
// <chrono> 讓我們能用 C++ 時間單位(例如 1s搭配計時器使用。
#include <chrono>
// 匯入 chrono 的字面常數,例如 1s, 100ms。
// 沒有這行的話,程式裡寫 1s 會編譯失敗。
using namespace std::chrono_literals;
// 定義一個節點類別,繼承 rclcpp::Node。
// 一個「節點Node」就是一個 ROS2 程式的執行單元,可以包含 Publisher/Subscriber/Service/Action 等。
class MyfristRos2_pub : public rclcpp::Node{
public:
MyfristRos2_pub():Node("node_pub"),count_(0){
publisher_=this->create_publisher<std_msgs::msg::String>("topic_for_vulue",10);
timer_ = this->create_wall_timer(
1s, std::bind(&MyfristRos2_pub::publish_message, this));
}
private:
}