創建節點
本節我們將創建一個控制節點和一個被控節點。
控制節點創建一個話題發布者publisher,發布控制命令(command)話題,接口類型為字符串(string),控制接點通過發布者發布控制命令(前進、后退、左轉、右轉、停止)。
被控節點創建一個訂閱者subscribe,訂閱控制命令,收到控制命令后根據命令內容打印對應速度出來。
創建publisher
依次輸入下面的命令,創建chapt3_ws工作空間、example_topic_rclcpp功能包和topic_publisher_01.cpp。
cd d2lros2/
mkdir -p chapt3/chapt3_ws/src
cd chapt3/chapt3_ws/src
ros2 pkg create example_topic_rclcpp --build-type ament_cmake --dependencies rclcpp
touch example_topic_rclcpp/src/topic_publisher_01.cpp
接著采用面向對象方式寫一個最簡單的節點。
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"class TopicPublisher01 : public rclcpp::Node
{
public:// 構造函數,有一個參數為節點名稱TopicPublisher01(std::string name) : Node(name){RCLCPP_INFO(this->get_logger(), "大家好,我是%s.", name.c_str());// 創建發布者command_publisher_ = this->create_publisher<std_msgs::msg::String>("command", 10);}private:// 聲明話題發布者rclcpp::Publisher<std_msgs::msg::String>::SharedPtr command_publisher_;
};int main(int argc, char **argv)
{rclcpp::init(argc, argv);/*創建對應節點的共享指針對象*/auto node = std::make_shared<TopicPublisher01>("topic_publisher_01");/* 運行節點,并檢測退出信號*/rclcpp::spin(node);rclcpp::shutdown();return 0;
}
修改CMakeLists.txt
add_executable(topic_publisher_01 src/topic_publisher_01.cpp)
ament_target_dependencies(topic_publisher_01 rclcpp)install(TARGETStopic_publisher_01DESTINATION lib/${PROJECT_NAME}
)
編寫發布者
學習使用API文檔
想要創建發布者,只需要調用node的成員函數create_publisher并傳入對應的參數即可。
rclcpp: rclcpp: ROS Client Library for C++ (www.ros2.org)
導入消息接口
依次做完這三步
CMakeLists.txt 新增
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)add_executable(topic_publisher_01 src/topic_publisher_01.cpp)
ament_target_dependencies(topic_publisher_01 rclcpp **std_msgs**)
packages.xml 新增
<buildtool_depend>ament_cmake</buildtool_depend><depend>rclcpp</depend><depend>std_msgs</depend><test_depend>ament_lint_auto</test_depend><test_depend>ament_lint_common</test_depend>
代碼文件topic_publisher_01.cpp 新增
#include "std_msgs/msg/string.hpp"class TopicPublisher01 : public rclcpp::Node
編譯
cd chapt3/chapt3_ws/
colcon build --packages-select example_topic_rclcpp
source install/setup.bash
ros2 run example_topic_rclcpp topic_publisher_01
使用定時器定時發布數據
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"class TopicPublisher01 : public rclcpp::Node
{
public:// 構造函數,有一個參數為節點名稱TopicPublisher01(std::string name) : Node(name){RCLCPP_INFO(this->get_logger(), "大家好,我是%s.", name.c_str());// 創建發布者command_publisher_ = this->create_publisher<std_msgs::msg::String>("command", 10);// 創建定時器,500ms為周期,定時發布timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&TopicPublisher01::timer_callback, this));}private:void timer_callback(){// 創建消息std_msgs::msg::String message;message.data = "forward";// 日志打印RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", message.data.c_str());// 發布消息command_publisher_->publish(message);}// 聲名定時器指針rclcpp::TimerBase::SharedPtr timer_;// 聲明話題發布者指針rclcpp::Publisher<std_msgs::msg::String>::SharedPtr command_publisher_;
};int main(int argc, char **argv)
{rclcpp::init(argc, argv);/*創建對應節點的共享指針對象*/auto node = std::make_shared<TopicPublisher01>("topic_publisher_01");/* 運行節點,并檢測退出信號*/rclcpp::spin(node);rclcpp::shutdown();return 0;
}
定時器
定時器是ROS2中的另外一個常用功能,通過定時器可以實現按照一定周期調用某個函數以實現定時發布等邏輯。
定時器對應的類是 rclcpp::TimerBase,調用create_wall_timer將返回其共享指針。
創建定時器時傳入了兩個參數,這兩個參數都利用了C++11的新特性。
std::chrono::milliseconds(500),代表500ms,chrono是c++ 11中的時間庫,提供計時,時鐘等功能。
std::bind(&TopicPublisher01::timer_callback, this),bind() 函數的意義就像它的函數名一樣,是用來綁定函數調用的某些參數的。
編寫訂閱者
topic_subscribe_01.cpp
cd chapt3_ws/src/example_topic_rclcpp
touch src/topic_subscribe_01.cpp
topic_subscribe_01.cpp
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"class TopicSubscribe01 : public rclcpp::Node
{
public:TopicSubscribe01(std::string name) : Node(name){RCLCPP_INFO(this->get_logger(), "大家好,我是%s.", name.c_str());// 創建一個訂閱者訂閱話題command_subscribe_ = this->create_subscription<std_msgs::msg::String>("command", 10, std::bind(&TopicSubscribe01::command_callback, this, std::placeholders::_1));}private:// 聲明一個訂閱者rclcpp::Subscription<std_msgs::msg::String>::SharedPtr command_subscribe_;// 收到話題數據的回調函數void command_callback(const std_msgs::msg::String::SharedPtr msg){double speed = 0.0f;if(msg->data == "forward"){speed = 0.2f;}RCLCPP_INFO(this->get_logger(), "收到[%s]指令,發送速度 %f", msg->data.c_str(),speed);}
};int main(int argc, char **argv)
{rclcpp::init(argc, argv);/*創建對應節點的共享指針對象*/auto node = std::make_shared<TopicSubscribe01>("topic_subscribe_01");/* 運行節點,并檢測退出信號*/rclcpp::spin(node);rclcpp::shutdown();return 0;
}
CMakeLists.txt
add_executable(topic_subscribe_01 src/topic_subscribe_01.cpp)
ament_target_dependencies(topic_subscribe_01 rclcpp std_msgs)install(TARGETS
topic_subscribe_01DESTINATION lib/${PROJECT_NAME}
)
packages.xml
不改動,同一個功能包,已經添加了。
編譯
cd chapt3/chapt3_ws/
colcon build --packages-select example_topic_rclcpp
source install/setup.bash
ros2 run example_topic_rclcpp topic_subscribe_01
手動運行測試
ros2 topic pub /command std_msgs/msg/String "{data: forward}"
運行測試
第一個終端
source install/setup.bash
ros2 run example_topic_rclcpp topic_subscribe_01
第二個終端
source install/setup.bash
ros2 run example_topic_rclcpp topic_publisher_01