NVIDIA Jetson Orin开发板,基于海康威视SDK拉流,在ROS2上发布图像话题

第一步:前往海康官网下载arm版SDK

点击[立即下载]

在终端中输入命令解压:

unzip HCNetSDKV6.1.9.45_build20220902_ArmLinux64_ZH_20250312150849

注意:这个压缩包的名称可能不一致

第二步:在本地构建工作空间

构建空目录和空文件如下

第三步:将解压好的海康SDK中的.so库文件复制到第二步构建的lib文件夹中

具体如下:

打开解压的海康SDK文件夹,找到MakeAll

将MakeAlL里面的所有.so文件以及HCNetSDKCom文件夹里面的.so文件全部复制到第二步本地构建工作空间的lib文件夹中。

第四步:将解压好的海康SDK中的.h头文件复制到第二步构建的include文件夹中

具体如下:

打开解压的海康SDK文件夹,找到incCn

将其中的全部.h文件复制到第二步本地构建工作空间的include文件夹中。

第五步:在本地构建工作空间的src文件夹中创建hik_camera_node.cpp文件

代码内容如下:

(注意:

①海康摄像头的IP地址、用户名、密码自行替换代码中的xxx.xxx.xxx.xxx。

②代码中初始化的参数flip是让发布的图像数据水平镜像翻转的,如果不需要,修改代码为flip = this->declare_parameter<bool>("flip", false);。

③代码中初始化的参数rotationAngle是让发布的图像数据旋转的,如果不需要,修改代码为rotationAngle = this->declare_parameter<int>("rotationAngle", 0);//0就是不旋转。

④在发布图像话题的时候,代码中自行将图像尺寸等比例缩放为宽度640,如果不需要,可以注释掉。

⑤发布图像话题频率在代码中设置为5hz,如果需要更快的发布频率,修改”if (time_since_last.seconds() > 0.15)“这块的代码。

)

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <chrono>
#include <thread>
#include <memory>
#include <functional>
#include <map>
#include <mutex>
// #include <iostream>
// #include <string>
// #include <yaml-cpp/yaml.h>
#include "HCNetSDK.h"
#include "LinuxPlayM4.h"


// 类定义
class HikCameraNode : public rclcpp::Node {
public:
    // 保存实例
    static std::mutex s_instance_mutex;  // +++ 新增静态互斥锁 +++
    static std::map<LONG, HikCameraNode*> s_camera_instances;
    HikCameraNode() : Node("hik_camera") {
        // 初始化参数
       device_ip_ = this->declare_parameter<std::string>("device_ip", "xxx.xxx.xxx.xxx");
       port_ = this->declare_parameter<int>("port", 8000);
       username_ = this->declare_parameter<std::string>("username", "xxx");
       password_ = this->declare_parameter<std::string>("password", "xxxx");
       flip = this->declare_parameter<bool>("flip", true); //true, false
       rotationAngle = this->declare_parameter<int>("rotationAngle", 10); //旋转10°
        // try {
        // // 加载YAML配置文件
        // YAML::Node config = YAML::LoadFile("src/config_image.yaml");

        // // 获取ros__parameters节点
        // const YAML::Node& params = config["get_image"]["ros__parameters"];

        // // 读取run_from的值
        // std::string run_from_str  = params["run_from"].as<std::string>();
        // // 转换为整数
        // int run_from_int = std::stoi(run_from_str);  // 字符串转整数
        // RCLCPP_INFO(this->get_logger(), "Run from: %d", run_from_int);

        // // 获取对应的chute_id配置
        // const YAML::Node& chute_config = params["chute_id"][run_from_int];
        // // 读取配置参数
        // std::string chute_name = chute_config["chute_name"].as<std::string>();
        // RCLCPP_INFO(this->get_logger(), "chute_name: %s", chute_name.c_str());
        // bool flip = chute_config["flip"].as<bool>();
        // RCLCPP_INFO(this->get_logger(), "flip: %s", flip ? "true" : "false");
        // std::string device_ip_ = chute_config["ip"].as<std::string>();
        // RCLCPP_INFO(this->get_logger(), "device_ip_: %s", device_ip_.c_str());
        // std::string username_ = chute_config["user"].as<std::string>();
        // std::string password_ = chute_config["passwd"].as<std::string>();
        // RCLCPP_INFO(this->get_logger(), "username_: %s, password_: %s", username_.c_str(), password_.c_str());
        // int rotationAngle = chute_config["rotationAngle"].as<int>();
        // RCLCPP_INFO(this->get_logger(), "rotationAngle: %d", rotationAngle);
        // }catch (const YAML::Exception& e) {
        // RCLCPP_FATAL(this->get_logger(), "Error reading YAML file");
        // }
        // 创建图像发布者
        publisher_ = this->create_publisher<sensor_msgs::msg::Image>("image_ori", 1);
        RCLCPP_INFO(this->get_logger(), "Image publisher created");

        // 初始化海康SDK
        if (!init_sdk()) {
            RCLCPP_FATAL(this->get_logger(), "SDK initialization failed");
            throw std::runtime_error("SDK init failed");
        }

        // 登录设备
        if (!login_device()) {
            RCLCPP_FATAL(this->get_logger(), "Device login failed");
            throw std::runtime_error("Login failed");
        }

        // 启动实时预览
        if (!start_real_play()) {
            RCLCPP_FATAL(this->get_logger(), "Real play start failed");
            throw std::runtime_error("Real play failed");
        }

        // 创建定时器保持节点运行
        // timer_ = this->create_wall_timer(
        //     std::chrono::seconds(5),
        //     [this]() { /* 保持节点运行 */ });
    }

    ~HikCameraNode() {
        stop_real_play();
        logout_device();
        cleanup_sdk();
        // 新增:从静态映射中移除当前实例
        if (real_handle_ >= 0) {
            if (!s_camera_instances.empty()) {
            s_camera_instances.erase(real_handle_);
        }  // 防止悬垂指针
        }
        RCLCPP_INFO(this->get_logger(), "Camera node shutdown");
    }

private:
    // 海康SDK相关变量
    std::string device_ip_;
    int port_;
    int rotationAngle;
    bool flip;
    std::string username_;
    std::string password_;
    int channel_ = -1;
    long user_id_ = -1;
    long real_handle_ = -1;
    int  play_port_ = -1;
    std::mutex play_mutex_;// 线程安全
    // ROS2相关
    rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
    rclcpp::TimerBase::SharedPtr timer_;
    size_t frame_count_ = 0;                     // 帧计数器
    rclcpp::Time last_publish_time_ = this->now(); // 记录上次发布时间

    // 初始化SDK
    bool init_sdk() {
        if (!NET_DVR_Init()) {
            RCLCPP_ERROR(this->get_logger(), "NET_DVR_Init failed! Error: %d", NET_DVR_GetLastError());
            return false;
        }
        NET_DVR_SetLogToFile(0, "./logs/");
        RCLCPP_INFO(this->get_logger(), "SDK initialized");
        return true;
    }

    // 清理SDK
    void cleanup_sdk() {
        NET_DVR_Cleanup();
        RCLCPP_INFO(this->get_logger(), "SDK cleaned up");
    }

    // 登录设备
    bool login_device() {
        NET_DVR_USER_LOGIN_INFO login_info = {0};
        NET_DVR_DEVICEINFO_V40 device_info = {0};

        login_info.bUseAsynLogin = 0;
        login_info.wPort = port_;
        strncpy(login_info.sDeviceAddress, device_ip_.c_str(), NET_DVR_DEV_ADDRESS_MAX_LEN);
        strncpy(login_info.sUserName, username_.c_str(), NAME_LEN);
        strncpy(login_info.sPassword, password_.c_str(), NAME_LEN);

        user_id_ = NET_DVR_Login_V40(&login_info, &device_info);

        if (user_id_ < 0) {
            RCLCPP_ERROR(this->get_logger(), "Login failed! Error: %d", NET_DVR_GetLastError());
            return false;
        }
        channel_ = device_info.struDeviceV30.byStartChan;
        RCLCPP_INFO(this->get_logger(), "Login success! User ID: %ld", user_id_);
        return true;
    }

    // 登出设备
    void logout_device() {
        if (user_id_ >= 0) {
            NET_DVR_Logout(user_id_);
            RCLCPP_INFO(this->get_logger(), "Logged out from device");
        }
    }

    // 启动实时预览
    bool start_real_play() {
        NET_DVR_PREVIEWINFO preview_info = {0};
        preview_info.hPlayWnd = 0;       // 不使用窗口
        preview_info.lChannel = channel_; // 通道号
        preview_info.dwStreamType = 0;    // 主码流
        preview_info.dwLinkMode = 0;      // TCP
        preview_info.bBlocked = 1;         // 阻塞取流
        preview_info.byVideoCodingType = 0; //码流数据编解码类型:0- 通用编码数据,1- 热成像探测器产生的原始数据(温度数据的加密信息,通过去加密运算,将原始数据算出真实的温度值)
        preview_info.byDataType  = 0;  //数据类型:0-码流数据,1-音频数据

        real_handle_ = NET_DVR_RealPlay_V40(user_id_, &preview_info, nullptr, nullptr);

        if (real_handle_ < 0) {
            RCLCPP_ERROR(this->get_logger(), "RealPlay failed! Error: %d", NET_DVR_GetLastError());
            return false;
        }
        // +++ 新增:存储实例到映射表 +++
        {
            std::lock_guard<std::mutex> lock(s_instance_mutex);
            s_camera_instances[real_handle_] = this;  // 核心修复
        }
        if (!NET_DVR_SetStandardDataCallBack(real_handle_, &standard_data_callback,
           real_handle_)) {
            RCLCPP_ERROR(this->get_logger(), "Set callback failed! Error: %d", NET_DVR_GetLastError());
            NET_DVR_StopRealPlay(real_handle_);
            return false;
        };

        RCLCPP_INFO(this->get_logger(), "RealPlay started successfully");
        return true;
    }

    // 停止实时预览
    void stop_real_play() {
        if (real_handle_ >= 0) {
            NET_DVR_StopRealPlay(real_handle_);
            RCLCPP_INFO(this->get_logger(), "RealPlay stopped");
        }
    }

    // 标准数据回调(静态成员函数)
    static void CALLBACK standard_data_callback(LONG lRealHandle, DWORD dwDataType,
                                              BYTE *pBuffer, DWORD dwBufSize,
                                              DWORD dwUser) {

         HikCameraNode* self = nullptr;
        {
            std::lock_guard<std::mutex> lock(s_instance_mutex);  // 加锁
            auto it = s_camera_instances.find(lRealHandle);
            if (it != s_camera_instances.end()) self = it->second;
        }
        if (!self || !rclcpp::ok()) return;
        // RCLCPP_INFO(self->get_logger(), "进入standard_data_callback方法");
        switch (dwDataType) {
            case NET_DVR_SYSHEAD:
                if (!PlayM4_GetPort(&self->play_port_)) break;
                RCLCPP_INFO(self->get_logger(), "进入系统头");
                PlayM4_SetStreamOpenMode(self->play_port_, STREAME_REALTIME);
                PlayM4_OpenStream(self->play_port_, pBuffer, dwBufSize, 1024 * 1024);
                PlayM4_SetDecCallBackMend(self->play_port_, &HikCameraNode::decode_callback, reinterpret_cast<void*>(self));
                PlayM4_Play(self->play_port_, 0);
                break;

            case NET_DVR_STREAMDATA:
                // RCLCPP_INFO(self->get_logger(), "进入复合流数据接收");
                if (self->play_port_ != -1) {
                    // RCLCPP_INFO(self->get_logger(), "进入PlayM4");
                    PlayM4_InputData(self->play_port_, pBuffer, dwBufSize);
                }
                break;
        }
    }

    // 解码回调(静态成员函数)
    static void CALLBACK decode_callback(int nPort, char* pBuf, int nSize,
                                        FRAME_INFO* pFrameInfo, void* pUser,
                                        int nReserved2) {

        auto self = reinterpret_cast<HikCameraNode*>(pUser);
        if (!self || !rclcpp::ok()) return;
        // RCLCPP_INFO(self->get_logger(), "进入decode_callback");
        // 图像尺寸校验
        if (pFrameInfo->nWidth <= 0 || pFrameInfo->nHeight <= 0 || nSize <= 0) {
            RCLCPP_ERROR(self->get_logger(), "Invalid frame data!");
            return;
        }

        std::lock_guard<std::mutex> lock(self->play_mutex_);
        if (self->play_port_ == -1) {
            PlayM4_GetPort(&self->play_port_);
        }
        if (pFrameInfo->nType == T_YV12) {
            // 创建YUV图像
            cv::Mat yv12_img(pFrameInfo->nHeight * 3/2, pFrameInfo->nWidth, CV_8UC1,
                            reinterpret_cast<uchar*>(pBuf));

            // 转换为BGR
            cv::Mat bgr_img;
            cv::cvtColor(yv12_img, bgr_img, cv::COLOR_YUV2BGR_YV12);
            if (bgr_img.empty()) { // 检查转换结果
            RCLCPP_ERROR(self->get_logger(), "YV12转BGR失败!");
            return;
            }
            // 按比例缩放图像
            if (bgr_img.cols > 640) {
                double scale = 640.0 / bgr_img.cols;
                cv::resize(bgr_img, bgr_img, cv::Size(), scale, scale, cv::INTER_LINEAR);
            }


            // 发布图像
            self->publish_image(bgr_img);
        }
    }

    // 发布图像到ROS2
    void publish_image(cv::Mat& bgr_img) {


        frame_count_++;
        auto current_time = this->now();
        auto time_since_last = current_time - last_publish_time_;

        // 当累计时间≥200ms(5Hz)时发布
        if (time_since_last.seconds() > 0.15) {
            last_publish_time_ = current_time;
            RCLCPP_INFO(this->get_logger(), "发布帧 (累计%ld帧)", frame_count_);
            // 旋转图像
            if (rotationAngle != 0) {
                cv::Point2f center(bgr_img.cols / 2.0f, bgr_img.rows / 2.0f);
                cv::Mat M = cv::getRotationMatrix2D(center, rotationAngle, 1.0);
                cv::warpAffine(bgr_img, bgr_img, M, bgr_img.size());
                RCLCPP_INFO_ONCE(this->get_logger(), "对画面旋转: %d", rotationAngle);
            }
            // RCLCPP_INFO(this->get_logger(), "flip: %s", flip ? "true" : "false");
            // 镜像翻转
            if (flip) {
                cv::flip(bgr_img, bgr_img, 1); // 1表示水平翻转
                RCLCPP_INFO_ONCE(this->get_logger(), "对画面镜像"); // ROS2日志记录
            }
            auto msg = cv_bridge::CvImage(
                std_msgs::msg::Header(),
                "bgr8",
                bgr_img
            ).toImageMsg();

            msg->header.stamp = this->now();
            msg->header.frame_id = "hik_camera";
            msg->width = bgr_img.cols;
            msg->height = bgr_img.rows;
            msg->step = static_cast<sensor_msgs::msg::Image::_step_type>(bgr_img.step);
            // RCLCPP_INFO(this->get_logger(), "Image published: %dx%d", bgr_img.cols, bgr_img.rows);
            publisher_->publish(*msg);
        }
    }
};
std::mutex HikCameraNode::s_instance_mutex;
std::map<LONG, HikCameraNode*> HikCameraNode::s_camera_instances;
int main(int argc, char** argv) {
    rclcpp::init(argc, argv);
    auto node = std::make_shared<HikCameraNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

第六步:本地构建工作空间的CMakeLists内容如下:

cmake_minimum_required(VERSION 3.8)
project(hik_camera_node)
#set(CMAKE_BUILD_TYPE Debug)
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -O0")
# ========== 基础配置 ==========
# 1. 设置C++标准
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)  # 强制使用C++14

# ========== 依赖管理 ==========
# 2. 查找ROS 2核心依赖包
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(image_transport REQUIRED)

# ========== 路径配置 ==========
# 3. 结构化头文件路径
include_directories(
  include
  ${PROJECT_SOURCE_DIR}/include/${PROJECT_NAME}  # 符合ROS 2规范
)

# 4. 添加海康SDK库搜索路径
link_directories(${PROJECT_SOURCE_DIR}/lib)

# ========== 目标构建 ==========
# 5. 声明可执行文件
add_executable(hik_camera_node 
  src/hik_camera_node.cpp
)

# 6. 链接ROS依赖
ament_target_dependencies(hik_camera_node
  rclcpp
  sensor_msgs
  cv_bridge
  image_transport
)

# 7. 链接海康SDK库(使用库标识名)
target_link_libraries(hik_camera_node
  hcnetsdk    # 对应libhcnetsdk.so
  PlayCtrl    # 对应libPlayCtrl.so
)

# 8. 设置RPATH确保运行时加载
set_target_properties(hik_camera_node PROPERTIES
  BUILD_WITH_INSTALL_RPATH TRUE
  INSTALL_RPATH "$ORIGIN/../lib"  # 相对路径查找
)

# ========== 安装规则 ==========
# 9.1 安装可执行文件
install(TARGETS hik_camera_node
  RUNTIME DESTINATION lib/${PROJECT_NAME}
)

# 9.2 安装配置文件
if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/config)
  install(DIRECTORY config/
    DESTINATION share/${PROJECT_NAME}/config
  )
endif()

# 9.3 安装海康SDK库(精确控制)
file(GLOB SDK_LIBS "${PROJECT_SOURCE_DIR}/lib/lib*.so*")  # 匹配所有库文件
install(FILES ${SDK_LIBS}
  DESTINATION lib/${PROJECT_NAME}
)

# 9.4 安装头文件(如果存在)
if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/include)
  install(DIRECTORY include/
    DESTINATION include/${PROJECT_NAME}
  )
endif()

# ========== 包声明 ==========
# 10. 生成ament包(必须最后调用)
ament_package()

第七步:本地构建工作空间的package内容如下:

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>hik_camera_node</name>
  <version>0.0.0</version>
  <description>TODO: Package description</description>
  <maintainer email="xxxxxxx@xxxxxx.com">nvidia</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <depend>rclcpp</depend>
  <depend>std_msgs</depend>
  <depend>cv_bridge</depend>
  <depend>sensor_msgs</depend>
  <depend>image_transport</depend>  <!-- 新增 -->
  <depend>libhcnetsdk</depend>     <!-- 海康SDK依赖 -->
  <depend>libPlayCtrl</depend>      <!-- 海康播放库 -->

  <export>
    <build_type>ament_cmake</build_type>
    <build_export_depend>libhcnetsdk</build_export_depend>
    <build_export_depend>libPlayCtrl</build_export_depend>
  </export>
</package>

第八步:在终端进入本地工作空间的根目录

终端运行ros2的编译命令:

colcon build

编译之后,在终端运行source:

source install/setup.bash

添加动态链接库路径:

export LD_LIBRARY_PATH=/home/你的用户名/你构建的工作空间/lib:$LD_LIBRARY_PATH

最后运行hik_camera_node:

ros2 run hik_camera_node hik_camera_node

在终端的输出:

也可以再开一个终端,在相同的工作目录输入:

export LD_LIBRARY_PATH=/home/你的用户名/你构建的工作空间/lib:$LD_LIBRARY_PATH
source install/setup.bash
rqt

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值