点击下方卡片,关注“机器视觉与AI深度学习”
视觉/图像重磅干货,第一时间送达!
前言
微信登录要扫二维码,手机支付要扫二维码,共享单车也要扫二维码。除了这些在日常生活中已经非常普及的扫码场景之外,二维码在工业生产中也已经普遍应用,比如使用二维码标记物料型号,或者在二维码中保存产品的生产信息,只要通过相机扫一扫,很快就可以看到对应的内容。
既然二维码可以保存很多信息,那有没有可能和机器人应用结合?当然没有问题,在很多机器人应用场景中也有广泛的二维码识别需求。二维码识别和机器人视觉巡线类似,大家同样可以使用ROS 2与OpenCV 结合的方式,让机器人识别二维码并执行预先在二维码中设定的一些动作。
二维码扫描库——Zbar
Zbar 是一个开源的条形码和二维码扫描库,可以用于快速识别和解码条形码和二维码。安装起来也非常简单,只需要执行以下命令:
$ sudo apt install libzbar-dev
Zbar库的功能主要包含以下四个部分:
1、图像获取与预处理 Zbar 首先需要获取输入图像,可以从相机捕获实时图像,也可以是已保存的静态图像文件。在处理之前,通常需要对图像进行预处理,如灰度化、降噪、边缘检测等操作,以提高后续解码的准确性和效率。
2、符号定位与定位模式 Zbar 使用图像处理技术来定位输入图像中的条形码或二维码符号。对于不同类型的符号(如二维码、一维条形码等),Zbar 会采用不同的定位算法和策略来确定符号的位置和边界。对于二维码,通常会检测其定位模式(Finder Patterns)以及可能的三个定位角。
3、符号解码 一旦符号被正确定位,Zbar 就会进行解码操作。对于一维条形码,这涉及到解析条形的宽度和间距信息,然后映射到特定的编码规则(如 EAN-13、Code 128 等)。对于二维码,Zbar 则会解析图案中的数据矩阵,根据 QR 码或 Data Matrix 码的编码规则提取数据。
4、数据输出与应用集成 Zbar 解码成功后,会输出识别到的数据内容,如文本、网址、数字等。这些数据可以被进一步处理,用于应用程序的功能实现,如自动填充表单、商品信息查询、登录验证等。
代码实现
class QrCodeDetection : public rclcpp::Node
{
public:
QrCodeDetection() : Node("qr_code_detection")
{
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
"/camera/image_raw", 10, std::bind(&QrCodeDetection::imageCallback, this, std::placeholders::_1));
qr_code_pub_ = this->create_publisher<std_msgs::msg::String>("qr_code", 10);
image_pub_ = this->create_publisher<sensor_msgs::msg::Image>("qr_code_image", 10);
}
private:
void imageCallback(const sensor_msgs::msg::Image::SharedPtr msg)
{
try {
cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
cv::Mat frame = cv_ptr->image;
cv::Mat gray;
cv::cvtColor(frame, gray, cv::COLOR_BGR2GRAY);
zbar::ImageScanner scanner;
scanner.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);
zbar::Image zbar_image(frame.cols, frame.rows, "Y800", (uchar *)gray.data, frame.cols * frame.rows);
scanner.scan(zbar_image);
for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
symbol != zbar_image.symbol_end(); ++symbol) {
std::string qr_code_data = symbol->get_data();
RCLCPP_INFO(this->get_logger(), "Scanned QR Code: %s", qr_code_data.c_str());
// 发布二维码数据
auto qr_code_msg = std_msgs::msg::String();
qr_code_msg.data = qr_code_data;
qr_code_pub_->publish(qr_code_msg);
// 在图像上绘制二维码边界和信息
std::vector<cv::Point> points;
for (int i = 0; i < symbol->get_location_size(); i++) {
points.push_back(cv::Point(symbol->get_location_x(i), symbol->get_location_y(i)));
}
cv::polylines(frame, points, true, cv::Scalar(0, 255, 0), 2);
cv::Point text_origin = points[0];
text_origin.y -= 10; // 将文本位置稍微上移
cv::putText(frame, qr_code_data, text_origin, cv::FONT_HERSHEY_SIMPLEX, 0.8, cv::Scalar(0, 255, 0), 2);
}
// 发布带有二维码标记的图像
sensor_msgs::msg::Image::SharedPtr out_img = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", frame).toImageMsg();
image_pub_->publish(*out_img);
}
catch (cv_bridge::Exception &e) {
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
return;
}
}
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr qr_code_pub_;
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr image_pub_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<QrCodeDetection>());
rclcpp::shutdown();
return 0;
}
重点分析下以上代码的关键内容:
subscription_ = this->create_subscription<sensor_msgs::msg::Image>(
"/camera/image_raw", 10, std::bind(&QrCodeDetection::imageCallback, this, std::placeholders::_1));
首先通过订阅图像话题的数据捕获到图像,每接收到一次图像消息就执行一次回调函数。正如下面的代码,每接收一次image话题数据就会执行一次imageCallback的代码。
// 遍历识别到的QR码
for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
symbol != zbar_image.symbol_end(); ++symbol) {
const char *qrCode_msg = symbol->get_data().c_str();
RCLCPP_INFO(this->get_logger(), "Scanned QR Code: %s", qrCode_msg);
auto sign_com_msg = std_msgs::msg::String();
sign_com_msg.data = qrCode_msg;
// 发布QR码内容
auto qr_code_msg = std_msgs::msg::String();
qr_code_msg.data = qr_code_data;
qr_code_pub_->publish(qr_code_msg);
在收到话题数据进入到回调函数后,进一步实现二维码的定位与解析。先按照要求将输入的图像进行灰度化处理,然后调用了Zbar的二维码定位和scan方法进行和识别,最终就可以将识别出来的结果给发布出来。
// 在图像上绘制二维码边界和信息
std::vector<cv::Point> points;
for (int i = 0; i < symbol->get_location_size(); i++) {
points.push_back(cv::Point(symbol->get_location_x(i), symbol->get_location_y(i)));
}
cv::polylines(frame, points, true, cv::Scalar(0, 255, 0), 2);
cv::Point text_origin = points[0];
text_origin.y -= 10; // 将文本位置稍微上移
cv::putText(frame, qr_code_data, text_origin, cv::FONT_HERSHEY_SIMPLEX, 0.8, cv::Scalar(0, 255, 0), 2);
}
// 发布带有二维码标记的图像
sensor_msgs::msg::Image::SharedPtr out_img = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", frame).toImageMsg();
image_pub_->publish(*out_img);
此外还可以将二维码结果和图像信息进行融合,大家可以使用以上OpenCV的接口进行实现。
运行结果