ROS 系列學習教程(總目錄)
ROS2 系列學習教程(總目錄)
目錄
- 1. 構造函數
- 2. 節點名稱相關
- 3. 獲取log對象句柄
- 4. 回調組相關
- 5. Topic發布與訂閱
- 6. Service服務端與客戶端
1. 構造函數
public:Node(const std::string & node_name, const NodeOptions & options = NodeOptions());Node(const std::string & node_name, const std::string & namespace_, const NodeOptions & options = NodeOptions());
protected:Node(const Node & other, const std::string & sub_namespace);
2. 節點名稱相關
獲取節點名稱
const char *get_name() const;
獲取節點名空間
const char *get_namespace() const;
獲取包含名空間和名稱的全名
const char *get_fully_qualified_name() const;
獲取當前 ROS 2 系統中所有活躍節點的名稱列表
std::vector<std::string> get_node_names() const;
獲取 ROS 2 系統中當前活躍的 主題(Topic)和 服務(Service)的名稱及其關聯的消息或服務類型
std::map<std::string, std::vector<std::string>> get_topic_names_and_types() const;
std::map<std::string, std::vector<std::string>> get_service_names_and_types() const;
獲取指定節點提供的所有服務名稱及其對應的服務類型列表
std::map<std::string, std::vector<std::string>>
get_service_names_and_types_by_node(const std::string & node_name,const std::string & namespace_) const;
3. 獲取log對象句柄
rclcpp::Logger get_logger() const;
4. 回調組相關
回調組是ROS 2中管理回調函數執行的重要機制,它允許開發者控制不同回調之間的執行關系。(后面會詳細介紹)
創建并返回一個回調組指針
rclcpp::CallbackGroup::SharedPtr create_callback_group(// 指定回調組的類型,枚舉值,決定回調組如何被調度執行rclcpp::CallbackGroupType group_type,// 決定是否自動將這個回調組添加到與節點關聯的執行器(executor)中bool automatically_add_to_executor_with_node = true);
遍歷節點中的所有回調組,并對每個有效的回調組執行給定的函數
void for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
5. Topic發布與訂閱
創建并返回一個發布者指針
std::shared_ptr<PublisherT>
create_publisher(const std::string & topic_name,const rclcpp::QoS & qos,const PublisherOptionsWithAllocator<AllocatorT> & options =PublisherOptionsWithAllocator<AllocatorT>()
);
參數說明:
topic_name
是topic的名字
qos
是服務質量策略設置(后面會詳細介紹)
options
高級選項配置。(高級應用場景)
使用示例:
auto node = std::make_shared<rclcpp::Node>("my_node");
// 創建一個發布者,發布 String 類型消息到 "/chatter" 主題
auto publisher = node->create_publisher<std_msgs::msg::String>("/chatter",rclcpp::QoS(10).reliable() // QoS 配置// 使用默認的 options
);
創建并返回一個訂閱者指針
std::shared_ptr<SubscriptionT>
create_subscription(const std::string & topic_name,const rclcpp::QoS & qos,CallbackT && callback,const SubscriptionOptionsWithAllocator<AllocatorT> & options =SubscriptionOptionsWithAllocator<AllocatorT>(),typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (MessageMemoryStrategyT::create_default())
);
參數說明:
topic_name
是topic的名字
qos
是服務質量策略設置(后面會詳細介紹)
callback
是回調函數。
options
高級選項配置。(高級應用場景)
msg_mem_strat
用于設置消息內存策略。(高級應用場景)
使用示例:
auto node = std::make_shared<rclcpp::Node>("subscriber_node");
auto callback = [](const std_msgs::msg::String::SharedPtr msg) { // Lambda 回調RCLCPP_INFO(node->get_logger(), "Received: %s", msg->data.c_str());
};// 創建一個訂閱者,接收 String 類型消息
auto subscription = node->create_subscription<std_msgs::msg::String>("/chatter",rclcpp::QoS(10),callback// 使用默認的 options 和 msg_mem_strat
);
統計當前訂閱到指定主題(Topic)的發布者(Publisher)數量
size_t count_publishers(const std::string & topic_name) const;
使用場景
-
動態拓撲監控
- 檢查某個主題是否有發布者,避免訂閱“無人發布”的主題。
- 示例:機器人傳感器主題
/lidar/data
的發布者是否在線。
-
條件性邏輯
- 根據發布者數量決定是否啟用某些功能。
if (node->count_publishers("/cmd_vel") > 0) {// 安全地訂閱 /cmd_vel,因為有發布者存在 }
-
調試與日志
- 記錄主題的發布者數量變化,診斷通信問題。
統計當前有多少訂閱者(Subscribers)正在訂閱指定的主題(Topic)
size_t count_subscribers(const std::string & topic_name) const;
使用場景
-
動態發布決策
- 檢查是否有訂閱者,避免無意義的數據發布(節省資源)
if (node->count_subscribers("/sensor_data") > 0) {publisher->publish(data); // 只在有訂閱者時發布 }
-
調試與監控
- 診斷通信問題(例如訂閱者未正確連接)。
- 日志記錄訂閱者數量變化。
-
條件性初始化
- 延遲初始化資源密集型組件,直到有訂閱者存在。
6. Service服務端與客戶端
創建Service客戶端
template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(const std::string & service_name,const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,rclcpp::CallbackGroup::SharedPtr group = nullptr);
參數說明:
service_name
:服務名稱
qos_profile
:服務質量(QoS)配置,默認值為 rmw_qos_profile_services_default
(ROS 2 默認的服務 QoS)
group
:回調組的智能指針,默認值為 nullptr
使用示例:
// 假設有一個服務類型:example_interfaces::srv::AddTwoInts
auto client = node->create_client<example_interfaces::srv::AddTwoInts>("/add_two_ints");// 發送請求
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = 2;
request->b = 3;
auto future = client->async_send_request(request);
創建Service服務端
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(const std::string & service_name,CallbackT && callback,const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,rclcpp::CallbackGroup::SharedPtr group = nullptr);
參數說明:
service_name
:服務名稱
callback
:Service的處理函數
qos_profile
:服務質量(QoS)配置,默認值為 rmw_qos_profile_services_default
(ROS 2 默認的服務 QoS)
group
:回調組的智能指針,默認值為 nullptr
使用示例:
auto node = std::make_shared<rclcpp::Node>("my_node");// 定義回調函數
auto callback = [](const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response
) {response->sum = request->a + request->b;
};// 創建服務
auto service = node->create_service<example_interfaces::srv::AddTwoInts>("/add_two_ints", callback);