- 其他ROS2學(xué)習(xí)筆記: ROS2學(xué)習(xí)筆記
- 代碼倉(cāng)庫(kù):Github連接地址
- 歡迎各位互相學(xué)習(xí)交流
2.1 ROS2話題通訊介紹
話題通信是一種單向通信模型,一方發(fā)布數(shù)據(jù),一方訂閱數(shù)據(jù),適用于連續(xù)不間斷的通訊場(chǎng)景,如小車SLAM導(dǎo)航過(guò)程中的位姿信息等等。話題是一個(gè)通訊的管道,ROS2的話題發(fā)布方和接收方無(wú)論是C/C++還是Python都可以發(fā)布/訂閱相同的話題實(shí)現(xiàn)通訊,一個(gè)話題的發(fā)布方,可以有多個(gè)訂閱方,如下圖所示:
Tips:節(jié)點(diǎn)(Node)的概念
ROS的通信對(duì)象的構(gòu)建都依賴于節(jié)點(diǎn)(回想之前快速體驗(yàn)的
rclcpp::Node
或者是from rclpy.node import Node
都是為了創(chuàng)建一個(gè)節(jié)點(diǎn)所導(dǎo)入的父類),一般情況下一個(gè)節(jié)點(diǎn)都對(duì)應(yīng)某一個(gè)功能模塊(例如一個(gè)節(jié)點(diǎn)負(fù)責(zé)持續(xù)發(fā)布SLAM位姿數(shù)據(jù)等),一個(gè)C/C++ 或者Python的文件代碼,可以包括多個(gè)節(jié)點(diǎn)。
2.2 ROS2常用的消息類型介紹
2.2.1 std_msgs消息類型
參考內(nèi)容
官方文檔 std_msgs Msg/Srv Documentation
詳解常用的ROS內(nèi)置消息類型
ROS中g(shù)eometry_msgs消息類型、nav_msg消息
std_msgs
屬于ROS的標(biāo)準(zhǔn)數(shù)據(jù)類型庫(kù),主要包括的消息類型有:
ROS type | C++ type |
---|---|
bool | bool |
byte | uint8_t |
char | char |
float32 | float |
float64 | double |
int8 | int8_t |
uint8 | uint8_t |
int16 | int16 |
uint16 | uint16 |
int32 | int32 |
uint32 | uint32 |
int64 | int64 |
uint64 | uint64_t |
string | std::string |
static array | std::array<T, N> |
數(shù)組和有條件的字符串的映射
ROS type | C++ type |
---|---|
unbounded dynamic array | std::vector |
bounded dynamic array | custom_class<T, N> |
bounded string | std::string |
2.2.2 geometry_msgs消息類型
參考內(nèi)容
官方文檔 geometry_msgs Msg/Srv Documentation
ROS中g(shù)eometry_msgs常用消息類型
ROS2 humble的接口官方API
geometry_msgs
:常見(jiàn)的幾何信息(如點(diǎn)、向量和姿勢(shì))提供ROS消息,其中包括的內(nèi)容有,具體的話題參數(shù),例如在使用烏龜節(jié)點(diǎn)控制烏龜運(yùn)動(dòng)的cmd_vel
話題就是采用geometry_msgs/Twist
編寫的,具體的用法,可以去查閱官網(wǎng)。
Accel
AccelStamped
AccelWithCovariance
AccelWithCovarianceStamped
Inertia
InertiaStamped
Point
Point32
PointStamped
Polygon
PolygonStamped
Pose
Pose2D
PoseArray
PoseStamped
PoseWithCovariance
PoseWithCovarianceStamped
Quaternion
QuaternionStamped
Transform
TransformStamped
Twist
TwistStamped
TwistWithCovariance
TwistWithCovarianceStamped
Vector3
Vector3Stamped
Wrench
WrenchStamped
2.3 使用C/C++創(chuàng)建基礎(chǔ)消息類型的話題通訊
參考內(nèi)容:
Writing a simple publisher and subscriber (C++)
2.2.2_話題通信_(tái)原生消息(C++)_01發(fā)布方01源碼分析
2.3.1 創(chuàng)建C/C++發(fā)布話題信息的功能包并配置VSCode環(huán)境
創(chuàng)建發(fā)布者功能包時(shí),不添加任何依賴項(xiàng),回顧之前的項(xiàng)目配置
- 創(chuàng)建ROS2 C/C++功能包,其中包名為
cppBaseMsgPub
:ros2 pkg create cppBaseMsgPub --build-type ament_cmake
Tips:這里補(bǔ)充還是推薦采用下劃線割開(kāi)的命名方式,否則容易出錯(cuò)
如果嘗試命名節(jié)點(diǎn)和依賴項(xiàng),可以直接采用這種方式,節(jié)點(diǎn)名為
cppBaseMsgPubNode
,依賴rclcpp
和std_msgs
:ros2 pkg create cppBaseMsgPub --build-type ament_cmake --node-name cppBaseMsgPubNode --dependencies rclcpp std_msgs
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ ros2 pkg create cppBaseMsgPub --build-type ament_cmake
going to create a new package
... 手動(dòng)省略
creating ./cppBaseMsgPub/CMakeLists.txt
[WARNING]: Unknown license 'TODO: License declaration'. This has been set in the package.xml, but no LICENSE file has been created.
It is recommended to use one of the ament license identitifers:
... 手動(dòng)省略
MIT-0
- 在工作空間(這個(gè)是vscode的概念)下創(chuàng)建
.vsocde
文件夾和settings.json
文件,配置VSCode的settings.json
文件,添加路徑
{
"C_Cpp.default.includePath": ["/opt/ros/humble/include/**"],
"python.analysis.extraPaths": ["/opt/ros/humble/local/lib/python3.10/dist-packages/"],
}
此時(shí)的文件結(jié)構(gòu)如下:可以看到,如果單純的指定了包名但是沒(méi)有指定節(jié)點(diǎn)名,不會(huì)在src
目錄下創(chuàng)建.cpp
文件
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ tree -a
.(注釋:這個(gè)就是工作空間)
├── cppBaseMsgPub
│ ├── CMakeLists.txt
│ ├── include
│ │ └── cppBaseMsgPub
│ ├── package.xml
│ └── src
└── .vscode
└── settings.json
5 directories, 3 files
完成之后配置VSCode環(huán)境
2.3.2 編寫ROS2發(fā)布話題節(jié)點(diǎn)CPP文件
- 編寫發(fā)布者代碼:根據(jù)官網(wǎng)提供的案例,在包的
src
目錄下,創(chuàng)建cppBaseMsgPubNode.cpp
文件,對(duì)cppBaseMsgPubNode.cpp
進(jìn)行發(fā)布者內(nèi)容編寫:總的來(lái)說(shuō),主要包括創(chuàng)建構(gòu)造發(fā)布節(jié)點(diǎn),計(jì)數(shù)屬性,然后綁定發(fā)布函數(shù)到定時(shí)器上
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
// C++14中的時(shí)間庫(kù)
using namespace std::chrono_literals;
class CppBaseMsgPub: public rclcpp::Node
{
public:
/* 1. ROS2節(jié)點(diǎn)的構(gòu)造函數(shù),其中包括一個(gè)node對(duì)象(初始化時(shí)候沒(méi)有給出節(jié)點(diǎn)的名稱),
* 和屬性count_(默認(rèn)初始化為0) */
CppBaseMsgPub(const char* nodeName):Node(nodeName), count_(0)
{
// 2. 創(chuàng)建發(fā)布者,參數(shù)分別為話題名稱myTopicName,和發(fā)布隊(duì)列的長(zhǎng)隊(duì)為10
publisher_ = this->create_publisher<std_msgs::msg::String>("myTopicName", 10);
// 3. 創(chuàng)建定時(shí)器,設(shè)置發(fā)布的頻率,并綁定定時(shí)執(zhí)行的事件,這里給到的是CppBaseMsgPub類的函數(shù)
timer_ = this->create_wall_timer(500ms, std::bind(&CppBaseMsgPub::timer_callback, this));
}
private:
// 4. 定義回調(diào)函數(shù)
void timer_callback()
{
auto message = std_msgs::msg::String();
message.data = "Hello, world! " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Cpp Publish: '%s'", message.data.c_str());
publisher_->publish(message);
}
// 5. 計(jì)時(shí)器、發(fā)布者和計(jì)數(shù)器字段的聲明
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
// 創(chuàng)建節(jié)點(diǎn),給出構(gòu)造的節(jié)點(diǎn)名為cppBaseMsgPubNode
rclcpp::spin(std::make_shared<CppBaseMsgPub>("cppBaseMsgPubNode"));
rclcpp::shutdown();
return 0;
}
2.3.3 配置C/C++發(fā)布話題功能包并編譯
- 配置
package.xml
:package.xml
主要對(duì)C/C++的功能包依賴項(xiàng)和發(fā)布信息進(jìn)行配置,由于在節(jié)點(diǎn)cppBaseMsgPubNode.cpp
中主要用到了rclcpp
和std_msgs
兩個(gè)依賴,因此package.xml
的配置主要如下:
<?xml version="1.0"?>
<?xml-model schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>cppBaseMsgPub</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="pldz@R7000.com">pldz</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<!-- 添加依賴項(xiàng) -->
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
- 配置
CmakeLists.txt
:主要包括的內(nèi)容有五部分,并且需要按照順序進(jìn)行配置好
find_package() // 1. 列出依賴項(xiàng),通俗的說(shuō)是項(xiàng)目編譯所需要的全部依賴項(xiàng)名稱,節(jié)點(diǎn)和項(xiàng)目是兩個(gè)概念,一個(gè)項(xiàng)目可以有多個(gè)節(jié)點(diǎn)
add_executable() // 2. 可執(zhí)行文件的路徑,通俗來(lái)說(shuō)是編譯節(jié)點(diǎn)的main函數(shù)入口
target_include_directories() // 3. 編譯節(jié)點(diǎn)所需要的include的位置
ament_target_dependencies() // 4. 編譯節(jié)點(diǎn)所需要的依賴項(xiàng),這一步的目的是連接編譯該節(jié)點(diǎn)所需要的依賴項(xiàng)
install() // 5. 通俗來(lái)說(shuō),是將編譯好的節(jié)點(diǎn)給拷貝到ROS功能包的目錄,使得能夠通過(guò)指令ros2 run <包名> <節(jié)點(diǎn)名>的配置,默認(rèn)這一步的目的就是將build文件夾的內(nèi)容拷貝到install的lib文件夾下
ament_package() // 6. 生成ament工具的環(huán)境,缺少這一步,無(wú)法在install文件夾下生成setup.bash文件等等
因此該項(xiàng)目的CmakeLists.txt
如下所示:
cmake_minimum_required(VERSION 3.8)
project(cppBaseMsgPub)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
# 1. 添加依賴項(xiàng)列表
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
# 2. 生成節(jié)點(diǎn)的主函數(shù)入口和節(jié)點(diǎn)名稱
add_executable(cppBaseMsgPubNode src/cppBaseMsgPubNode.cpp)
# 3. Include路徑配置,這里其實(shí)沒(méi)有用上,可以不用配置
target_include_directories(cppBaseMsgPubNode PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
# 4. ament工具的編譯所需要的依賴
ament_target_dependencies(
cppBaseMsgPubNode
"rclcpp"
"std_msgs"
)
# 5. 安裝規(guī)則
install(TARGETS cppBaseMsgPubNode
DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
# 6. 配置ament環(huán)境,生成功能包
ament_package()
- 編譯功能包:
colcon build
:
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ colcon build
WARNING: Package name "cppBaseMsgPub" does not follow the naming conventions. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes.
Starting >>> cppBaseMsgPub
... 手動(dòng)省略
Summary: 1 package finished [4.44s]
1 package had stderr output: cppBaseMsgPub
- 運(yùn)行節(jié)點(diǎn):激活功能包環(huán)境
source ./install/setup.bash
,然后運(yùn)行ros2 run cppBaseMsgPub cppBaseMsgPubNode
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ source ./install/setup.bash
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ ros2 run cppBaseMsgPub cppBaseMsgPubNode
[INFO] [1683015931.213646661] [cppBaseMsgPubNode]: Cpp Publish: 'Hello, world! 0'
[INFO] [1683015931.713349843] [cppBaseMsgPubNode]: Cpp Publish: 'Hello, world! 1'
[INFO] [1683015932.213429705] [cppBaseMsgPubNode]: Cpp Publish: 'Hello, world! 2'
^C[INFO] [1683015932.588202160] [rclcpp]: signal_handler(signum=2)
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$
2.3.4 創(chuàng)建C/C++訂閱話題的功能包
- 由于上面操作過(guò)一遍從功能包開(kāi)始的配置節(jié)點(diǎn)依賴項(xiàng),這里直接提前在創(chuàng)建功能包的時(shí)候直接指定依賴項(xiàng),省去后續(xù)的配置,取名訂閱話題的功能包為
cppBaseMsgSub
,節(jié)點(diǎn)名稱為cppBaseMsgSubNode
,如ros2 pkg create cppBaseMsgSub --build-type ament_cmake --node-name cppBaseMsgSubNode --dependencies rclcpp std_msgs
Tips:這里補(bǔ)充還是推薦采用下劃線割開(kāi)的命名方式,否則容易出錯(cuò)
pldz@pldz-pc:~/share/ROS2_DEMO/2_Chapter/code$ ros2 pkg create cppBaseMsgSub --build-type ament_cmake --node-name cppBaseMsgSubNode --dependencies rclcpp std_msgs
going to create a new package
package name: cppBaseMsgSub
... 手動(dòng)省略
MIT
MIT-0
- 2.3.1節(jié)在工作空間下配置過(guò)vscode的
settings.json
這里就不再配置vscode了
2.3.5 編寫ROS2訂閱話題節(jié)點(diǎn)CPP文件
- 直接在
cppBaseMsgSubNode.cpp
文件進(jìn)行編輯,創(chuàng)建訂閱節(jié)點(diǎn),訂閱話題myTopicName
與之前的發(fā)布話題類型和名稱一致即可:
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
// 占位符,結(jié)合std::bind函數(shù)的綁定使用
using std::placeholders::_1;
class CppBaseMsgSub: public rclcpp::Node
{
public:
/* 1. ROS2節(jié)點(diǎn)的構(gòu)造函數(shù) */
CppBaseMsgSub(const char* nodeName):Node(nodeName)
{
// 2.聲明訂閱話題類型,并綁定回調(diào)函數(shù)
subscription_ = this->create_subscription<std_msgs::msg::String>(
"myTopicName", 10, std::bind(&CppBaseMsgSub::topic_callback, this, _1));
}
private:
// 3. 定義訂閱到消息的回調(diào)函數(shù)
void topic_callback(const std_msgs::msg::String & msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
}
// 4. 計(jì)時(shí)器、發(fā)布者和計(jì)數(shù)器字段的聲明
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
// 初始化訂閱節(jié)點(diǎn)
rclcpp::spin(std::make_shared<CppBaseMsgSub>("cppBaseMsgSubNode"));
rclcpp::shutdown();
return 0;
}
2.3.6 配置C/C++訂閱話題功能包并編譯
- 由于是直接在創(chuàng)建包的時(shí)候指定了依賴項(xiàng),可以直接編譯
colcon build
,運(yùn)行查看效果:
2.4 使用Python創(chuàng)建基礎(chǔ)消息類型的話題通訊
2.4.1 創(chuàng)建Python發(fā)布話題功能包并編寫節(jié)點(diǎn)文件
- 創(chuàng)建Python發(fā)布者功能包,其中功能包名稱為
pythonBaseMsgPub
,不指定節(jié)點(diǎn)名和依賴項(xiàng),后續(xù)手動(dòng)配置packages.xml
和setup.py
:ros2 pkg create pythonBaseMsgPub --build-type ament_python
,目前文件結(jié)構(gòu)如下所示:
Tips:這里補(bǔ)充還是推薦采用下劃線割開(kāi)的命名方式,否則容易出錯(cuò)
- 在
pythonBaseMsgPub/pythonBaseMsgPub
文件夾下創(chuàng)建pythonBaseMsgPubNode.py
文件,內(nèi)容如下所示
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class PythonBaseMsgPub(Node):
def __init__(self, nodeName):
# 1. 初始化父類構(gòu)造函數(shù),其中節(jié)點(diǎn)名需要?jiǎng)?chuàng)建時(shí)候指定,計(jì)數(shù)屬性count_從0開(kāi)始
super().__init__(nodeName)
self.count_ = 0
# 2. 聲明發(fā)布者,發(fā)布消息類型為String,話題名為myTopicName,隊(duì)列大小為10
self.publisher_ = self.create_publisher(String, 'myTopicName', 10)
# 3. 創(chuàng)建定時(shí)器,其中更新頻率為0.5秒,并綁定回調(diào)函數(shù)
self.timer = self.create_timer(0.5, self.timer_callback)
# 4. 定義回調(diào)函數(shù)
def timer_callback(self):
msg = String()
msg.data = 'Hello World: %d' % self.count_
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.count_ += 1
def main(args=None):
rclpy.init(args=args)
pythonBaseMsgPubNode = PythonBaseMsgPub("pythonBaseMsgPubNode")
rclpy.spin(pythonBaseMsgPubNode)
# 銷毀節(jié)點(diǎn)
pythonBaseMsgPubNode.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
2.4.2 配置Python項(xiàng)目并運(yùn)行
- 配置Python項(xiàng)目的
packages.xml
:主要是添加可執(zhí)行的依賴項(xiàng)rclpy
和std_msgs
<?xml version="1.0"?>
<?xml-model schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>pythonBaseMsgPub</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="pldz@R7000.com">pldz</maintainer>
<license>TODO: License declaration</license>
<!-- 與C/C++不同的是,Python文件是一個(gè)可執(zhí)行的腳本,因此依賴項(xiàng)的關(guān)鍵字為exec_depend -->
<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>
<export>
<build_type>ament_python</build_type>
</export>
</package>
- 配置
setup.py
文件指定節(jié)點(diǎn)的main
函數(shù)入口:
from setuptools import setup
package_name = 'pythonBaseMsgPub'
setup(
name=package_name,
version='0.0.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='pldz',
maintainer_email='pldz@R7000.com',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
# 指定編譯節(jié)點(diǎn)的main函數(shù)入口
entry_points={
'console_scripts': [
'pythonBaseMsgPubNode = pythonBaseMsgPub.pythonBaseMsgPubNode:main',
],
},
)
- 編譯:
colcon build
2.4.3 創(chuàng)建Python訂閱話題功能包并編寫節(jié)點(diǎn)
- 創(chuàng)建功能包
pythonBaseMsgSub
,并直接給出節(jié)點(diǎn)名pythonBaseMsgSubNode
和依賴項(xiàng)rclpy
和std_msgs
,如下所示:ros2 pkg create pythonBaseMsgSub --build-type ament_python --node-name pythonBaseMsgSubNode --dependencies rclpy std_msgs
Tips:這里補(bǔ)充還是推薦采用下劃線割開(kāi)的命名方式,否則容易出錯(cuò)
- 編寫訂閱者節(jié)點(diǎn):
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class PythonBaseMsgSub(Node):
def __init__(self, nodeName):
# 1. 構(gòu)造函數(shù),初始化node節(jié)點(diǎn)
super().__init__(nodeName)
# 2. 聲明訂閱者,訂閱話題`myTopicNmae`,并綁定回調(diào)函數(shù)
self.subscription = self.create_subscription(String,'myTopicName',self.listener_callback,10)
# 3. 定義回調(diào)函數(shù)
def listener_callback(self, msg):
self.get_logger().info('I heard: "%s"' % msg.data)
def main(args=None):
rclpy.init(args=args)
pythonBaseMsgSubNode = PythonBaseMsgSub("pythonBaseMsgSubNode")
rclpy.spin(pythonBaseMsgSubNode)
pythonBaseMsgSubNode.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
2.4.4 編譯運(yùn)行節(jié)點(diǎn)
-
由于指定了依賴項(xiàng)和節(jié)點(diǎn)名,不需要多余的進(jìn)行
packages.xml
和setup.py
的配置 -
編譯
colcon build
,聯(lián)合C/C++的一起運(yùn)行,可以看到話題通訊是多對(duì)多的文章來(lái)源:http://www.zghlxwxcb.cn/news/detail-434636.html
文章來(lái)源地址http://www.zghlxwxcb.cn/news/detail-434636.html
到了這里,關(guān)于2 ROS2話題通訊基礎(chǔ)(1)的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!