5.5.2 模型推理
模型推理开发
功能背景
hobot_dnn
是TogetheROS.Bot软件栈中的板端算法推理框架,在RDK上利用BPU处理器实现算法推理功能,基于D-Robotics算法推理框架和ROS2 Node进行二次开发,为机器人应用开发提供更简单易用的模型集成开发接口,包括模型管理、基于模型描述的输入处理及结果解析,以及模型输出内存分配管理等功能。
通过阅读本章节,用户可以使用D-Robotics提供的模型,在RDK上基于hobot_dnn
创建并运行一个人体检测的算法Node。借助tros.b提供的组件,订阅摄像头采集&发布的图像,对图像进行算法推理检测出人体框后,使用多目标跟踪(multi-target tracking
,即MOT
)算法对检测框进行跟踪和目标编号分配,最终实现在PC端的Web浏览器上实时渲染展示图像、人体框检测和目标跟踪结果。
前置条件
1 RDK开发板,并且已安装好相关软件,包括:
-
Ubuntu 20.04/Ubuntu 22.04系统镜像。
-
tros.b软件包。
-
ROS2软件包构建、编译等工具。安装命令:
sudo apt install ros-dev-tools
2 RDK已安装F37或者GC4663摄像头。
3 可以通过网络访问RDK的PC。
关于hobot_dnn)的详细使用说明可以参考
hobot_dnn)代码中的README.md和接口说明文档。hobot_dnn的使用逻辑流程如下:
在不了解hobot_dnn)使用流程的情况下,用户也可以按照本章节流程使用
hobot_dnn)开发出模型推理示例。
本章节以下内容使用tros.b Foxy版本举例说明,如果您使用的是tros.b Humble版本,只需将source /opt/tros/setup.bash
命令替换为source /opt/tros/humble/setup.bash
。
任务内容
1 创建package
mkdir -p ~/dev_ws/src
cd ~/dev_ws/src
source /opt/tros/setup.bash
ros2 pkg create --build-type ament_cmake cpp_dnn_demo --dependencies rclcpp sensor_msgs hbm_img_msgs ai_msgs dnn_node hobot_mot
cd cpp_dnn_demo
touch src/body_det_demo.cpp
2 编写示例
查看创建后的工程路径如下:
root@ubuntu:~# cd ~
root@ubuntu:~# tree dev_ws/
dev_ws/
└── src
└── cpp_dnn_demo
├── CMakeLists.txt
├── include
│ └── cpp_dnn_demo
├── package.xml
└── src
└── body_det_demo.cpp
5 directories, 3 files
在RDK上使用vi/vim等工具打开创建的代码源文件body_det_demo.cpp
:vi ~/dev_ws/src/cpp_dnn_demo/src/body_det_demo.cpp
拷贝如下代码到文件中:
#include "dnn_node/dnn_node.h"
#include "dnn_node/util/image_proc.h"
#include "dnn_node/util/output_parser/detection/fasterrcnn_output_parser.h"
#include "sensor_msgs/msg/image.hpp"
#include "ai_msgs/msg/perception_targets.hpp"
#include "hbm_img_msgs/msg/hbm_msg1080_p.hpp"
#include "hobot_mot/hobot_mot.h"
// 创建算法推理输出数据结构,添加消息头信息成员
struct FasterRcnnOutput : public hobot::dnn_node::DnnNodeOutput {
std::shared_ptr<std_msgs::msg::Header> image_msg_header = nullptr;
};
// 继承DnnNode虚基类,创建算法推理节点
class BodyDetNode : public hobot::dnn_node::DnnNode {
public:
BodyDetNode(const std::string &node_name = "body_det",
const rclcpp::NodeOptions &options = rclcpp::NodeOptions());
protected:
// 实现基类的纯虚接口,用于配置Node参数
int SetNodePara() override;
// 实现基类的虚接口,将解析后的模型输出数据封装成ROS Msg后发布
int PostProcess(const std::shared_ptr<hobot::dnn_node::DnnNodeOutput> &node_output)
override;
private:
// 算法模型输入图片数据的宽和高
int model_input_width_ = -1;
int model_input_height_ = -1;
// 人体检测框结果对应的模型输出索引
const int32_t box_output_index_ = 1;
// 检测框输出索引集合
const std::vector<int32_t> box_outputs_index_ = {box_output_index_};
// 图片消息订阅者
rclcpp::SubscriptionHbmem<hbm_img_msgs::msg::HbmMsg1080P>::ConstSharedPtr
ros_img_subscription_ = nullptr;
// 算法推理结果消息发布者
rclcpp::Publisher<ai_msgs::msg::PerceptionTargets>::SharedPtr
msg_publisher_ = nullptr;
// 多目标跟踪算法引擎
std::shared_ptr<HobotMot> hobot_mot_ = nullptr;
// 图片消息订阅回调
void FeedImg(const hbm_img_msgs::msg::HbmMsg1080P::ConstSharedPtr msg);
};
BodyDetNode::BodyDetNode(const std::string & node_name, const rclcpp::NodeOptions & options) :
hobot::dnn_node::DnnNode(node_name, options) {
// Init中使用BodyDetNode子类实现的SetNodePara()方法进行算法推理的初始化
if (Init() != 0 ||
GetModelInputSize(0, model_input_width_, model_input_height_) < 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_demo"), "Node init fail!");
rclcpp::shutdown();
}
// 创建消息订阅者,从摄像头节点订阅图像消息
ros_img_subscription_ =
this->create_subscription_hbmem<hbm_img_msgs::msg::HbmMsg1080P>(
"/hbmem_img", 10, std::bind(&BodyDetNode::FeedImg, this, std::placeholders::_1));
// 创建消息发布者,发布算法推理消息
msg_publisher_ = this->create_publisher<ai_msgs::msg::PerceptionTargets>(
"/cpp_dnn_demo", 10);
// 创建多目标跟踪(MOT)算法引擎
hobot_mot_ = std::make_shared<HobotMot>("config/iou2_method_param.json");
}
int BodyDetNode::SetNodePara() {
if (!dnn_node_para_ptr_) return -1;
// 指定算法推理使用的模型文件路径和模型名
dnn_node_para_ptr_->model_file = "config/multitask_body_kps_960x544.hbm";
dnn_node_para_ptr_->model_name = "multitask_body_kps_960x544";
return 0;
}
void BodyDetNode::FeedImg(const hbm_img_msgs::msg::HbmMsg1080P::ConstSharedPtr img_msg) {
if (!rclcpp::ok()) {
return;
}
// 对订阅到的图片消息进行验证,本示例只支持处理NV12格式图片数据
if (!img_msg) return;
if ("nv12" != std::string(reinterpret_cast<const char*>(img_msg->encoding.data()))) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_demo"), "Only support nv12 img encoding!");
return;
}
// 根据模型输入图片分辨率,使用DnnNode中提供的方法创建模型输入数据
auto inputs = std::vector<std::shared_ptr<hobot::dnn_node::DNNInput>>{
hobot::dnn_node::ImageProc::GetNV12PyramidFromNV12Img(
reinterpret_cast<const char*>(img_msg->data.data()),
img_msg->height, img_msg->width, model_input_height_, model_input_width_)};
// 创建模型输出数据,填充消息头信息
auto dnn_output = std::make_shared<FasterRcnnOutput>();
dnn_output->image_msg_header = std::make_shared<std_msgs::msg::Header>();
dnn_output->image_msg_header->set__frame_id(std::to_string(img_msg->index));
dnn_output->image_msg_header->set__stamp(img_msg->time_stamp);
// 以异步模式运行推理
Run(inputs, dnn_output, nullptr, false);
}
int BodyDetNode::PostProcess(const std::shared_ptr<hobot::dnn_node::DnnNodeOutput> &node_output) {
if (!rclcpp::ok()) {
return 0;
}
// 验证输出数据的有效性
if (node_output->outputs.empty() ||
static_cast<int32_t>(node_output->outputs.size()) < box_output_index_) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_demo"), "Invalid outputs");
return -1;
}
// 创建解析输出数据
// 检测框results的维度等于检测出来的目标类别数
std::vector<std::shared_ptr<hobot::dnn_node::parser_fasterrcnn::Filter2DResult>>
results;
// 关键点数据
std::shared_ptr<hobot::dnn_node::parser_fasterrcnn::LandmarksResult> output_body_kps = nullptr;
// 使用hobot dnn内置的Parse解析方法,解析算法输出
if (hobot::dnn_node::parser_fasterrcnn::Parse(node_output, nullptr,
box_outputs_index_, -1, -1, results, output_body_kps) < 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_node_sample"),
"Parse node_output fail!");
return -1;
}
auto filter2d_result = results.at(box_output_index_);
if (!filter2d_result) return -1;
// 将算法推理输出的人体检测框转成MOT算法输入数据类型
std::vector<MotBox> in_box_list;
for (auto& rect : filter2d_result->boxes) {
in_box_list.emplace_back(
MotBox(rect.left, rect.top, rect.right, rect.bottom, rect.conf));
}
// 根据消息头计算当前帧的时间戳
auto fasterRcnn_output =
std::dynamic_pointer_cast<FasterRcnnOutput>(node_output);
time_t time_stamp =
fasterRcnn_output->image_msg_header->stamp.sec * 1000 +
fasterRcnn_output->image_msg_header->stamp.nanosec / 1000 / 1000;
// 创建MOT算法的输出:带有目标编号的人体检测框和消失的目标编号
std::vector<MotBox> out_box_list;
std::vector<std::shared_ptr<MotTrackId>> disappeared_ids;
// 运行多目标跟踪算法
if (hobot_mot_->DoProcess(in_box_list,
out_box_list,
disappeared_ids,
time_stamp,
model_input_width_,
model_input_height_) < 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_demo"), "Do mot fail");
return -1;
}
// 创建用于发布推理结果的ROS Msg
ai_msgs::msg::PerceptionTargets::UniquePtr pub_data(
new ai_msgs::msg::PerceptionTargets());
// 将消息头填充到ROS Msg
pub_data->header.set__stamp(fasterRcnn_output->image_msg_header->stamp);
pub_data->header.set__frame_id(fasterRcnn_output->image_msg_header->frame_id);
// 将算法推理输出帧率填充到ROS Msg
if (node_output->rt_stat) {
pub_data->set__fps(round(node_output->rt_stat->output_fps));
// 如果算法推理统计有更新,输出算法模型输入和输出的帧率统计
if (node_output->rt_stat->fps_updated) {
RCLCPP_WARN(rclcpp::get_logger("dnn_demo"),
"input fps: %.2f, out fps: %.2f",
node_output->rt_stat->input_fps,
node_output->rt_stat->output_fps);
}
}
for (auto& rect : out_box_list) {
// 验证目标跟踪结果的有效性
if (rect.id < 0) {
continue;
}
// 将目标跟踪结果和检测框填充到ROS Msg
ai_msgs::msg::Target target;
target.set__type("person");
target.set__track_id(rect.id);
ai_msgs::msg::Roi roi;
roi.type = "body";
roi.rect.set__x_offset(rect.x1);
roi.rect.set__y_offset(rect.y1);
roi.rect.set__width(rect.x2 - rect.x1);
roi.rect.set__height(rect.y2 - rect.y1);
target.rois.emplace_back(roi);
pub_data->targets.emplace_back(std::move(target));
}
// 将消失的目标填充到ROS Msg
for (const auto& id_info : disappeared_ids) {
if (id_info->value < 0 ||
hobot_mot::DataState::INVALID == id_info->state_) {
continue;
}
ai_msgs::msg::Target target;
target.set__type("person");
target.set__track_id(id_info->value);
ai_msgs::msg::Roi roi;
roi.type = "body";
target.rois.emplace_back(roi);
pub_data->disappeared_targets.emplace_back(std::move(target));
}
// 发布ROS Msg
msg_publisher_->publish(std::move(pub_data));
return 0;
}
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<BodyDetNode>());
rclcpp::shutdown();
return 0;
}
2.1 Node设计
示例的人体检测算法Node主要包含三部分逻辑独立的功能。
(1)Node初始化和启动
配置算法使用的模型信息,创建算法推理消息的发布者和图像消息的订阅者,启动目标跟踪算法引擎。
(2)订阅消息和算法推理
在创建图像消息订阅者时,注册了消息回调FeedImg
,实现图像数据的处理并用于算法模型推理,回调中不等待算法推理完成。
(3)推理结果的处理和发布
算法推理完成后,通过注册的回调PostProcess
输出推理结果,回调中对检测结果进行多目标跟踪算法(HobotMot
)处理后,发布算法推理结果消息。
Node的设计和流程逻辑如下图:
2.2 代码说明
添加头文件
推理框架头文件dnn_node/dnn_node.h
,用于算法模型管理和推理。
算法模型输入处理头文件dnn_node/util/image_proc.h
,用于算法模型输入图片处理。
算法模型输出解析方法头文件dnn_node/util/output_parser/detection/fasterrcnn_output_parser.h
,用于模型推理完成后,从输出地址解析出结构化数据(对于本示例使用的人体检测算法,对应的结构化数据为人体检测框)。
ROS Msg头文件,用于消息的订阅和发布。
MOT算法引擎头文件,用于对检测出的人体框进行目标跟踪。
#include "dnn_node/dnn_node.h"
#include "dnn_node/util/image_proc.h"
#include "dnn_node/util/output_parser/detection/fasterrcnn_output_parser.h"
#include "sensor_msgs/msg/image.hpp"
#include "ai_msgs/msg/perception_targets.hpp"
#include "hbm_img_msgs/msg/hbm_msg1080_p.hpp"
#include "hobot_mot/hobot_mot.h"
创建算法推理输出数据结构
继承hobot_dnn)中的
DnnNodeOutput`基类,添加消息头信息成员,用于表示推理输出对应的图片信息。
struct FasterRcnnOutput : public hobot::dnn_node::DnnNodeOutput {
std::shared_ptr<std_msgs::msg::Header> image_msg_header = nullptr;
};
创建算法推理Node
继承hobot_dnn)中的
DnnNode虚基类,定义算法推理节点
BodyDetNode,实现
DnnNode`中定义的虚接口。
int SetNodePara()
:配置模型参数。
int PostProcess(const std::shared_ptr<hobot::dnn_node::DnnNodeOutput> &node_output)
:推理结果回调,将解析后结构化的模型输出数据封装成ROS Msg后发布。
class BodyDetNode : public hobot::dnn_node::DnnNode {
public:
BodyDetNode(const std::string &node_name = "body_det",
const rclcpp::NodeOptions &options = rclcpp::NodeOptions());
protected:
int SetNodePara() override;
int PostProcess(const std::shared_ptr<hobot::dnn_node::DnnNodeOutput> &node_output)
override;
实现BodyDetNode子类的构造
BodyDetNode
子类的构造函数中进行Node的初始化,同时通过GetModelInputSize
接口获取了模型输入图片的尺寸,包括图片的宽model_input_width_
和高model_input_height_
,用于模型前处理,不同的模型一般输入图片的尺寸不同。
通过零拷贝的通信方式,创建图片消息的订阅者,从摄像头节点订阅图像消息,用于算法模型推理。订阅的topic为/hbmem_img
,消息类型为tros.b中定义的图片消息类型hbm_img_msgs::msg::HbmMsg1080P
。
创建消息发布者,用于发布算法推理消息。发布的topic为/cpp_dnn_demo
,消息类型为tros.b中定义的算法消息类型ai_msgs::msg::PerceptionTargets
。
创建多目标跟踪(MOT)算法引擎,用于对每个人体检测框进行目标跟踪。
BodyDetNode
构造函数实现:
BodyDetNode::BodyDetNode(const std::string & node_name, const rclcpp::NodeOptions & options) :
hobot::dnn_node::DnnNode(node_name, options) {
// Init中使用BodyDetNode子类实现的SetNodePara()方法进行算法推理的初始化
if (Init() != 0 ||
GetModelInputSize(0, model_input_width_, model_input_height_) < 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn_demo"), "Node init fail!");
rclcpp::shutdown();
}
// 创建消息订阅者,从摄像头节点订阅图像消息
ros_img_subscription_ =
this->create_subscription_hbmem<hbm_img_msgs::msg::HbmMsg1080P>(
"/hbmem_img", 10, std::bind(&BodyDetNode::FeedImg, this, std::placeholders::_1));
// 创建消息发布者,发布算法推理消息
msg_publisher_ = this->create_publisher<ai_msgs::msg::PerceptionTargets>(
"/cpp_dnn_demo", 10);
// 创建多目标跟踪(MOT)算法引擎
hobot_mot_ = std::make_shared<HobotMot>("config/iou2_method_param.json");
}
其中Init()
是DnnNode
基类中定义并实现的接口,执行算法推理初始化,只做pipeline的串联,具体的SetNodePara()
步骤由用户(子类中)实现。串联的初始化流程如下:
int DnnNode::Init() {
RCLCPP_INFO(rclcpp::get_logger("dnn"), "Node init.");
int ret = 0;
// 1. set model info in node para
ret = SetNodePara();
if (ret != 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn"), "Set node para failed!");
return ret;
}
// check node para
if (ModelTaskType::InvalidType == dnn_node_para_ptr_->model_task_type) {
RCLCPP_ERROR(rclcpp::get_logger("dnn"), "Invalid model task type");
return -1;
}
// 2. model init
ret = dnn_node_impl_->ModelInit();
if (ret != 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn"), "Model init failed!");
return ret;
}
// 3. set output parser
ret = SetOutputParser();
if (ret != 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn"), "Set output parser failed!");
return ret;
}
// 4. task init
ret = dnn_node_impl_->TaskInit();
if (ret != 0) {
RCLCPP_ERROR(rclcpp::get_logger("dnn"), "Task init failed!");
return ret;
}
return ret;
}
配置模型参数
配置算法推理使用的模型文件路径和模型名。
int BodyDetNode::SetNodePara() {
if (!dnn_node_para_ptr_) return -1;
dnn_node_para_ptr_->model_file = "config/multitask_body_kps_960x544.hbm";
dnn_node_para_ptr_->model_name = "multitask_body_kps_960x544";
return 0;
}
实现图片订阅结果回调
创建DNNInput
类型的模型输入数据。订阅到的消息中包含图片信息(图片的编码方式、内容数据和分辨率等信息),使用hobot_dnn)中的算法模型输入图片处理接口
hobot::dnn_node::ImageProc::GetNV12PyramidFromNV12Img