目 录
@tros安装使用与ros2-Humble Zero-Copy使用
1. tros资料
TogetheROS.Bot是D-Robotics面向机器人厂商和生态开发者推出的机器人操作系统,旨在释放机器人场景的智能潜能,助力生态开发者和商业客户能够高效、便捷的进行机器人开发,打造具有竞争力的智能机器人产品。
主要特性如下:
- 提供“hobot_sensor”适配机器人常用传感器,节省开发时间,聚焦核心竞争力
- 提供“hobot_dnn”简化板端算法模型推理与部署,释放BPU算力,降低智能算法使用门槛
- 提供“hobot_codec”软硬结合加速视频编解码,节省CPU资源,提升并行处理能力
- 提供“hobot_cv”软硬结合提升常见CV算子性能,节省CPU资源,提升运行效率
- 提供“hobot Render”Web端和HDMI动态可视化功能,实时渲染算法结果(仅限Web端),便于展示与调试
- 增加“zero-copy”进程间零拷贝通信机制,降低数据传输时延,减少系统资源消耗
- 丰富中间件软件调试以及性能调优工具,提升问题定位效率,方便系统性能优化
- 与ROS2 Foxy/Humble版本接口保持完全兼容,便于复用ROS丰富工具包,加快原型验证
- 支持最小化和模块化剪裁,方便根据需要部署在资源受限的嵌入式产品中
#地瓜机器人官网首页
https://developer.d-robotics.cc
# 论坛(新手上路,安装编译使用一些问题可以提问,他们回复的效率很高)
https://developer.d-robotics.cc/forumList?id=6&title=%E6%96%B0%E6%89%8B%E4%B8%8A%E8%B7%AF
#教程
https://developer.d-robotics.cc/rdk_doc/Quick_start
# 文件服务器
https://archive.d-robotics.cc/TogetheROS/source_code/
2. tros源码安装
2.1 安装系统需求
项目 | 平台 | 操作系统 | 科学上网 |
---|---|---|---|
要求 | X86_64 | Ubuntu20.04 | need |
2.2 安装步骤
(1)设置locale 和 启用universe 软件源
sudo apt update && sudo apt install locales
sudo locale-gen en_US en_US.UTF-8
sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8
export LANG=en_US.UTF-8
sudo apt install software-properties-common
sudo add-apt-repository universe
(2)下载gpg密钥文件并添加源列表
sudo apt update && sudo apt install curl
sudo curl -sSL http://archive.d-robotics.cc/keys/sunrise.gpg -o /usr/share/keyrings/sunrise.gpg
echo "deb [arch=amd64 signed-by=/usr/share/keyrings/sunrise.gpg] http://archive.d-robotics.cc/ubuntu-rdk-sim focal main" | sudo tee /etc/apt/sources.list.d/sunrise.list > /dev/null
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
(3) 安装工具
sudo apt update && sudo apt install -y \
libbullet-dev \
python3-pip \
python3-pytest-cov \
ros-dev-tools
(4) 获取源码
git config --global credential.helper store
mkdir -p ~/cc_ws/tros_ws/src
cd ~/cc_ws/tros_ws/
git clone https://github.com/D-Robotics/robot_dev_config.git -b humble
cd robot_dev_config
# 切换版本到2.0.0 目前最高版本是2.2.3 但2.0.0以上的版本不支持x86平台
git reset --hard tros_2.0.0
cd ..
vcs-import src < ./robot_dev_config/ros2_release.repos
# 也可以从文件服务器直接下载源码
(5)安装依赖项
# install some pip packages needed for testing
python3 -m pip install -U \
argcomplete \
flake8-blind-except \
flake8-builtins \
flake8-class-newline \
flake8-comprehensions \
flake8-deprecated \
flake8-docstrings \
flake8-import-order \
flake8-quotes \
pytest-repeat \
pytest-rerunfailures \
pytest
# install Fast-RTPS dependencies
sudo apt install --no-install-recommends -y \
libasio-dev \
libtinyxml2-dev
# install Cyclone DDS dependencies
sudo apt install --no-install-recommends -y \
libcunit1-dev
# install tros.b basic models
sudo apt install --no-install-recommends -y \
hobot-models-basic
# install other packages dependencies
sudo apt install --no-install-recommends -y \
qt5-qmake \
libpyside2-dev \
libshiboken2-dev \
pyqt5-dev \
python3-pyqt5 \
python3-pyqt5.qtsvg \
python3-pyside2.qtsvg \
python3-sip-dev \
shiboken2 \
libyaml-dev \
qtbase5-dev \
libzstd-dev \
libeigen3-dev \
libxml2-utils \
libtinyxml-dev \
libssl-dev \
python3-numpy \
libconsole-bridge-dev \
pydocstyle \
libqt5core5a \
libqt5gui5 \
libgtest-dev \
cppcheck \
tango-icon-theme \
libqt5opengl5 \
libqt5widgets5 \
python3-lark \
libspdlog-dev \
google-mock \
clang-format \
python3-flake8 \
libbenchmark-dev \
python3-pygraphviz \
python3-pydot \
python3-psutil \
libfreetype6-dev \
libx11-dev \
libxaw7-dev \
libxrandr-dev \
libgl1-mesa-dev \
libglu1-mesa-dev \
python3-pytest-mock \
python3-mypy \
default-jdk \
libcunit1-dev \
libopencv-dev \
python3-ifcfg \
python3-matplotlib \
graphviz \
uncrustify \
python3-lxml \
libcppunit-dev \
libcurl4-openssl-dev \
python3-mock \
python3-nose \
libsqlite3-dev \
pyflakes3 \
clang-tidy \
python3-lttng \
liblog4cxx-dev \
python3-babeltrace \
python3-pycodestyle \
libassimp-dev \
libboost-dev \
libboost-python-dev \
python3-opencv \
libboost-python1.71.0
(6)编译
# 使用build.sh编译
bash ./robot_dev_config/build.sh -p X86
(7)安装tros.b
# 将编译生成的install目录拷贝至/opt目录下并重名为tros,与deb安装目录保持一致
Enjoy it!!!
3. Zero-copy
3.1 功能背景
通信是机器人开发引擎的基础功能,原生ROS2 Foxy进行大数据量通信时存在时延较大、系统负载较高等问题。TogetheROS.Bot Foxy基于RDK系统软件库hbmem实现了“zero-copy”功能,数据跨进程传输零拷贝,可大大减少大块数据传输延时和系统资源占用。本节介绍如何使用tros.b Foxy和Humble创建publisher和subscriber node进行大块数据传输,并计算传输延时。
ROS2 官方文档:
https://docs.ros.org/en/humble/Tutorials/Advanced/FastDDS-Configuration.html#
ROS2 官方代码:
https://github.com/ros2/demos/blob/humble/demo_nodes_cpp/src/topics/talker_loaned_message.cpp
3.2 TROS 关于zero-copy 使用总结(tros 官方文档)
3.3 零拷贝实现的基本原理
零拷贝是基于共享内存机制实现的,tros与ros2(dds)零拷贝功能均是基于boost interprocess库实现的,该库提供了共享内存、内存映射、相对指针、文件锁和消息队列等功能。
以ros2消息发布订阅为例:
(1)非零拷贝
消息流向如下图所示:

发布端消息依次通过ros2软件层、中间件接口层,将消息传给中间件,中间件负责将ros消息转换成DDS数据结构(序列化),转换过程涉及一次拷贝操作;
DDS发现机制通知中间件将DDS 消息转换成ros消息(反序列化),该转换过程又执行一次拷贝操作;
在消息发布订阅过程中,出现了多次拷贝操作,占用CPU 资源,会造成消息订阅延迟
(2)零拷贝
ros2 零拷贝发布订阅基本流程如下图所示,发布端通过租借发布队列中的消息地址,将需要发布的消息直接填充到发布队列中,订阅端会检测是否是可租借信息,从订阅队列中直接读取数据。该过程减少了拷贝操作,降低了cpu使用率和消息延迟。

4. ROS2 Humble zero-copy 使用
4.1 配置FASTDDS
在 .bashrc 中加入下列配置项目
#选者中间件为FASTDDS
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
# 开启消息租借
export ROS_DISABLE_LOANED_MESSAGES=0
# 使用xml配置qos
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
# qos配置文件地址
export FASTRTPS_DEFAULT_PROFILES_FILE=/home/fjz/system/config/ros2_shm/ros2_shm.xml
qos配置文件如下
<?xml version="1.0" encoding="UTF-8"?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<data_writer profile_name="default publisher profile" is_default_profile="true">
<qos>
<publishMode>
<kind>ASYNCHRONOUS</kind>
</publishMode>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</data_writer>
<data_reader profile_name="default subscription profile" is_default_profile="true">
<qos>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
<historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy>
</data_reader>
</profiles>
4.2 发布端
// 客户端创建
// 用于shared_mem方式发布图片
rclcpp::Publisher<hbm_img_msgs::msg::HbmMsg1080P>::SharedPtr publisher_hbmem_ = nullptr;
// 客户端实例化
publisher_hbmem_ = this->create_publisher<hbm_img_msgs::msg::HbmMsg1080P>(msg_pub_topic_name_, 5);
// 租借消息
auto loanedMsg = publisher_hbmem_->borrow_loaned_message();
if (loanedMsg.is_valid()) {
auto &msg = loanedMsg.get();
msg.height = image_cache_.height;
msg.width = image_cache_.width;
memcpy(msg.encoding.data(), "jpeg", strlen("jpeg"));
RCLCPP_WARN(rclcpp::get_logger("image_pub_node"), "create img");
memcpy(&msg.data[0], image_cache_.img_data, image_cache_.data_len);
struct timespec time_start = {0, 0};
clock_gettime(CLOCK_REALTIME, &time_start);
msg.time_stamp.sec = time_start.tv_sec;
msg.time_stamp.nanosec = time_start.tv_nsec;
msg.index = ++image_cache_.count_;
msg.data_size = image_cache_.data_len;
// 消息发布
publisher_hbmem_->publish(std::move(loanedMsg));
}
4.3 订阅端
// 客户端创建
rclcpp::Subscription<hbm_img_msgs::msg::HbmMsg1080P>::SharedPtr hbmem_subscription_ = nullptr;
// 客户端实例化
hbmem_subscription_ =
this->create_subscription<hbm_img_msgs::msg::HbmMsg1080P>(in_sub_topic_, 5,
std::bind(&HobotCodecNode::in_hbmem_topic_cb, this,std::placeholders::_1));
// 订阅回调
void HobotCodecNode::in_hbmem_topic_cb(const hbm_img_msgs::msg::HbmMsg1080P::ConstSharedPtr msg) {
if (!rclcpp::ok()) {
return;
}
// 消息处理
}
4.4 验证
#终端输入如下指令
lsof /dev/shm/fast_datasharing*
#输出类似结果
COMMAND PID USER FD YTPE DEVICE SIZE/OFF NODE NAME
hobot_ima 506947 fjz mem REG 0,27 37327708 131868 /dev/shm/fast_datasharing_01.0f.ce.9d.43.bc.18.51.00.00.00.00_0.0.12.3
hobot_ima 506947 fjz mem REG 0,27 21640 131867 /dev/shm/fast_datasharing_01.0f.ce.9d.45.bc.df.ff.00.00.00.00_0.0.1e.4
hobot_cod 506949 fjz mem REG 0,27 37327708 131868 /dev/shm/fast_datasharing_01.0f.ce.9d.43.bc.18.51.00.00.00.00_0.0.12.3
hobot_cod 506949 fjz mem REG 0,27 21640 131867 /dev/shm/fast_datasharing_01.0f.ce.9d.45.bc.df.ff.00.00.00.00_0.0.1e.4
4.5消息结构
(1) 中间件不支持non-POD 消息进行zero-copy
名词解释:POD(Plain Old Data)类型可通过浅拷贝或memcpy进行复制,而non-POD类型则需要逐元素复制。
--------引用自《Learning Boost C++ Libraries》第296页
zero-copy 的实现是需要提前申请固定内存地址,因此需要在申请时就明确消息的大小。
ros2 消息中对于可变数组、字符串变量都属于non-POD类型,FAST-DDS 不支持该类型的消息执行borrow_loaned_message()操作。
(2)自定义消息
对于大数据消息,需要重新定义消息结构才能使用zero-copy
例如图像数据可定义为如下结构:
int32 index
builtin_interfaces/Time time_stamp
uint32 height
uint32 width
uint32 data_size
uint32 step
uint8[12] encoding
uint8[6220800] data
uint32 MAX_SIZE=6220800
这个消息可表示1920x1080 三通道图像数据
(3) 建议
对于自定义消息,尽可能少使用non-POD类型数据
5. zero-copy 测试
5.1 系统环境
操作系统 | ros版本 | DDS版本 | cpu | 内存 |
---|---|---|---|---|
ubuntu22.04 | humble | FASTDDS | inter i5-13500H × 16 | 16GB |
5.2 测试结果
(1)订阅延迟
不同方式订阅延迟统计如下表所示
项目 | max(ms) | min(ms) | delta(ms) | average(ms) | std(ms) |
---|---|---|---|---|---|
non-zero-copy | 1.40142 | 0.280619 | 1.120801 | 0.791064422 | 0.163388865 |
zero-copy | 0.830889 | 0.166893 | 0.663996 | 0.497281271 | 0.096468941 |
从上图、表中可以看出,使用zero-copy 方式,订阅延迟较小且更稳定,非zero-copy 订阅延迟较大,并且受到cpu性能影响,延迟不稳定。
(2)cpu使用率
根据PID查询进程cpu使用率
ps -p <pid> -o pid,etimes,time,%cpu
项目 | 发布端 | 订阅端 |
---|---|---|
non-zero-copy | 0.9% | 11.5% |
zero-copy | 0.6% | 11.1% |
从上表可以看出使用zero-copy方式发布和订阅消息均可以降低CPU使用率
订阅端的cpu使用率较高原因:
a.日志打印较多
b.订阅到图像后进行了解码并重新发布成ros消息,用于rviz显示。