海康威视热成像双光谱MINI云台摄像改ros驱动

     海康威视热成像双光谱MINI云台摄像改ros驱动

 海康威视  型号:DS-2TD5567T-7/W

 
支持实时视频预览,实时视频转opencv,实时视频转ros消息,通过rviz预览

海康威视热成像双光谱MINI云台摄像改ros驱动_第1张图片

  

     主要代码:   consoleMain.cpp



#ifndef __APPLE__

#include 
#include 
#include 
#include 
#include "GetStream.h"
#include "public.h"
#include "ConfigParams.h"
#include "Alarm.h"
#include "CapPicture.h"
#include "playback.h"
#include "Voice.h"
#include "tool.h"
#include 

#include 
#include "maindecte_msgs/Msgdata.h"
#include "maindecte_srvs/maindecte.h"
#include 
#include 
#include 
#include 
#include "opencv2/xfeatures2d.hpp"
#include 

using namespace cv;
using namespace std;

 int lUserID_ =0;
//全局变量
 Mat g_BGRImage;
 LONG nPort = -1;
 ros::Publisher pub;
 bool whileFig=true;

/**
 * 海康摄像头ros驱动
 * 苏凯
 * 邮箱: [email protected]
 * 2023-03-27
 * rosrun haikangdecte haikangdecte_node
 */



 void CALLBACK DecCBFun(LONG nPort, char* pBuf, LONG nSize, FRAME_INFO* pFrameInfo, void* nReserved1, LONG nReserved2) {
     if (pFrameInfo->nType == T_YV12)
     {
         if (g_BGRImage.empty())
         {
             g_BGRImage.create(pFrameInfo->nHeight, pFrameInfo->nWidth, CV_8UC3);
         }
         Mat YUVImage(pFrameInfo->nHeight + pFrameInfo->nHeight / 2, pFrameInfo->nWidth, CV_8UC1, (unsigned char*)pBuf);
         cvtColor(YUVImage, g_BGRImage, COLOR_YUV2BGR_YV12);
         sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", g_BGRImage).toImageMsg();
         pub.publish(img_msg);
         YUVImage.~Mat();
     }
 }


 void CALLBACK fRealDataCallBack(LONG lRealHandle, DWORD dwDataType, BYTE *pBuffer, DWORD dwBufSize, void *pUser)
 {

     switch (dwDataType)
     {
         case NET_DVR_SYSHEAD:
             if (!PlayM4_GetPort(&nPort))
             {
                 break;
             }
             //m_iPort = lPort;
             if (dwBufSize > 0)
             {
                 if (!PlayM4_SetStreamOpenMode(nPort, STREAME_REALTIME))
                 {
                     break;
                 }
                 if (!PlayM4_OpenStream(nPort, pBuffer, dwBufSize, 10 * 1024 * 1024))
                 {
                     break;
                 }
                 if (!PlayM4_Play(nPort, NULL))
                 {
                     break;
                 }
                 if (!PlayM4_SetDecCallBack(nPort, DecCBFun))
                 {
                     break;
                 }
             }
             break;
         case NET_DVR_STREAMDATA:
             if (dwBufSize > 0 && nPort != -1)
             {
                 if (!PlayM4_InputData(nPort, pBuffer, dwBufSize))
                 {
                     cout << "error" << PlayM4_GetLastError(nPort) << endl;

                     break;
                 }
             }
             break;
         default:
             if (dwBufSize > 0 && nPort != -1)
             {
                 if (!PlayM4_InputData(nPort, pBuffer, dwBufSize))
                 {

                     break;
                 }
             }
             break;
     }

 }


 bool callback(maindecte_srvs::maindecte::Request &request, maindecte_srvs::maindecte::Response &response) {

     std::cout << "entry function" << std::endl;
     int lRealPlayHandle;
     NET_DVR_PREVIEWINFO struPlay = {0};
     struPlay.hPlayWnd = NULL;
     struPlay.lChannel = 1;
     struPlay.dwStreamType = 0;
     struPlay.dwLinkMode = 0;
     struPlay.bBlocked = 0;
     lRealPlayHandle = NET_DVR_RealPlay_V40(lUserID_, &struPlay, NULL, NULL);
     //*camera_RealPlay = lRealPlayHandle;

     if (lRealPlayHandle < 0)
     {
         printf("pyd---NET_DVR_RealPlay_V40 error, %d\n", NET_DVR_GetLastError());
     }
     else
     {
         std::cout << "NET_DVR_RealPlay_V40 success" << std::endl;
     }

     int msgtype =  request.msgtype;
     maindecte_msgs::Msgdata msgdata=  request.msgdata;

     int dwPTZCommand=  request.dwPTZCommand;//云台控制命令
     int dwStop=  request.dwStop;//0开始, 1停止
     int dwSpeed= request.dwSpeed;//速度 范围(1-7)

     std::string return_msg = "ok";
     std::cout << "MSG_type " << msgtype << std::endl;

     // NET_DVR_GET_FOCUSING_POSITION_STATE;
     switch (msgtype)
     {
         case 500001:  //云台控制
         {
             try
             {

                 std::cout << "云台控制 500001" << std::endl;
                 std::cout << "云台控制 0 开始 1停止:" << dwStop<7)
                     dwSpeed=7;

                 int error1 = NET_DVR_PTZControlWithSpeed(lRealPlayHandle, dwPTZCommand, dwStop,dwSpeed);
                 if (error1 < 0)
                 {
                     printf("pyd---500001云台控制  error, %d\n", NET_DVR_GetLastError());
                     //NET_DVR_Cleanup();

                 }
                 break;
             }
             catch (std::exception &e)
             {
                 std::cout << "exception : " << e.what() << std::endl;
             }
             break;
         }
         default:
             break;
     }



     NET_DVR_StopRealPlay(lRealPlayHandle);
     response.result=return_msg;
     return true;
 }

 void signalHandler(int signum)
 {

     whileFig=false;
     ros::shutdown();
 }

//rosrun haikangdecte haikangdecte_node
 int main(int argc,char *argv[])
{

    //节点名
    string nodeName = "haikangdecte_node";
    //初始化节点
    ros::init(argc,argv,nodeName);
    //创建节点
    ros::NodeHandle nh_;
    ros::NodeHandle private_nh("~");
    signal(SIGINT, signalHandler);
    //创建Service Server
    const ros::ServiceServer &server = nh_.advertiseService("/maindecte_service", callback);
    pub = nh_.advertise("/hikrobot/camera/image", 1);

    ros::AsyncSpinner spinner(1); // Use 4 threads
    spinner.start();


    NET_DVR_Init();
    Demo_SDK_Version();
    NET_DVR_SetLogToFile(3, "./sdkLog");
    char cUserChoose = 'r';
    
    //Login device
    NET_DVR_USER_LOGIN_INFO struLoginInfo = {0};
    NET_DVR_DEVICEINFO_V40 struDeviceInfoV40 = {0};
    struLoginInfo.bUseAsynLogin = false;

    struLoginInfo.wPort = 8000;
    memcpy(struLoginInfo.sDeviceAddress, "10.9.162.175", NET_DVR_DEV_ADDRESS_MAX_LEN);//10.8.98.80
    memcpy(struLoginInfo.sUserName, "admin", NAME_LEN);//admin
    memcpy(struLoginInfo.sPassword, "Admin123", NAME_LEN);//hik12345

     lUserID_ = NET_DVR_Login_V40(&struLoginInfo, &struDeviceInfoV40);

    if (lUserID_ < 0)
    {
        printf("pyd---Login error, %d\n", NET_DVR_GetLastError());
        printf("Press any key to quit...\n");
        cin>>cUserChoose;

        NET_DVR_Cleanup();
        return HPR_ERROR;
    }


    NET_DVR_PREVIEWINFO struPlayInfo = { 0 };
    struPlayInfo.hPlayWnd = NULL;         //需要SDK解码时句柄设为有效值,仅取流不解码时可设为空
    struPlayInfo.lChannel = 1;           //预览通道号
    struPlayInfo.dwStreamType = 1;       //0-主码流,1-子码流,2-码流3,3-码流4,以此类推
    struPlayInfo.dwLinkMode = 0;         //0- TCP方式,1- UDP方式,2- 多播方式,3- RTP方式,4-RTP/RTSP,5-RSTP/HTTP
    struPlayInfo.bBlocked = 0; //0- 非阻塞取流, 1- 阻塞取流
    LONG   lRealPlayHandle = NET_DVR_RealPlay_V40(lUserID_, &struPlayInfo, fRealDataCallBack, NULL);
    if (lRealPlayHandle < 0)
    {
        printf("NET_DVR_RealPlay_V40 error\n");
        printf("%d\n", NET_DVR_GetLastError());
        NET_DVR_Logout(lUserID_);
        NET_DVR_Cleanup();
        return 1;
    }

    while (ros::ok()&&whileFig)
    {
        std::this_thread::sleep_for(std::chrono::milliseconds(100));
    }


    // 停止预览
    NET_DVR_StopRealPlay(lRealPlayHandle);
    // 注销登录
    NET_DVR_Logout(lUserID_);
    //logout
    NET_DVR_Logout_V30(lUserID_);
    // 释放SDK资源
    NET_DVR_Cleanup();
    return 0;
}

#endif

cmakelist.txt

cmake_minimum_required(VERSION 3.0.2)
project(haikangdecte)

## Compile as C++11, supported in ROS Kinetic and newer
#add_compile_options(-std=c++11)
#add_compile_options(-MMD -MP )
#add_compile_options(-std=c++11 )
#add_compile_options(-std=c++14 )
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
add_compile_options(-std=c++11)
add_compile_options(-std=c++14)
#CXXFLAGS += -MMD -MP
#CXXFLAGS += -std=c++11

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages

# 寻找OpenCV库


set(OpenCV_DIR /home/sukai/3rdparty/opencv4.5.0/build/install/lib/cmake/opencv4 )
set(OPENCV_EXTRA_MODULES_PATH /home/sukai/3rdparty/opencv4.5.0/opencv_contrib-4.5.0/modules)
set(OPENCV_ENABLE_NONFREE ON)
# 设置OpenCV的编译选项
add_definitions(-DOPENCV_ENABLE_NONFREE=ON)

#find_package(OpenCV REQUIRED)
find_package(OpenCV REQUIRED QUIET)
include_directories(${OpenCV_INCLUDE_DIRS})


find_package(catkin REQUIRED COMPONENTS
  roscpp
  rosmsg
  rospy
        cv_bridge
        image_transport
        sensor_msgs
        std_srvs
        maindecte_msgs
        maindecte_srvs
)


#if (POLICY CMP0072)
    #set(OpenGL_GL_PREFERENCE LEGACY)
    #set(OpenGL_GL_PREFERENCE GLVND)

#endif()

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
#find_package(SQLite3 REQUIRED)
## System dependencies are found with CMake's conventions  报错以及相关boost问题 https://blog.csdn.net/qq_43111963/article/details/117869259 ||cmake与boost版本不兼容[1] https://stackoverflow.com/questions/65560775/cmake-new-boost-version-may-have-incorrect-or-missing-dependencies-and-importe


# OpenCV
#find_package(OpenCV REQUIRED QUIET)
#find_package(Eigen3 REQUIRED QUIET)

#find_package(MPI REQUIRED)
#find_package(Threads REQUIRED)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()



################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend tag for "message_generation"
##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
##     but can be declared for certainty nonetheless:
##     * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
#   FILES
#   Message1.msg
#   Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
#   DEPENDENCIES
#   std_msgs  # Or other packages containing msgs
# )

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
##   * add "dynamic_reconfigure" to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * uncomment the "generate_dynamic_reconfigure_options" section below
##     and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
#   cfg/DynReconf1.cfg
#   cfg/DynReconf2.cfg
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
#catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES contNav
#  CATKIN_DEPENDS roscpp rosmsg rospy
#  DEPENDS system_lib
#)


catkin_package(
        #  INCLUDE_DIRS include
        #  LIBRARIES visualOrientation
        #  CATKIN_DEPENDS roscpp rosmsg rospy
        #  DEPENDS system_lib
        #CATKIN_DEPENDS geometry_msgs roscpp rosmsg rospy  tf
       # CATKIN_DEPENDS geometry_msgs roscpp rosmsg rospy  tf
)
###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
   include
  ${catkin_INCLUDE_DIRS}
        #/usr/include/mysql
        /usr/local/include
        ${PCL_INCLUDE_DIRS}
        #${OpenCV_INCLUDE_DIRS}



        /home/sukai/3rdparty/opencv4.5.0/build/install/include  #ubuntu20.04
        #  /usr/include/eigen3
        #/usr/local/include/opencv4
)

# find / -name "libAudioRender.so" 2>/dev/null
link_directories(
        #/home/shi/docker/3rtparty/opencv4.5.0/build/install/lib   #opencv_world.so
        #/usr/local/lib   #ubuntu18.04
        #/home/sukai/3rtparty/opencv4.5.0/build/install/lib  #ubuntu20.04
        lib
        linux64/lib
        linux64/proj
        linux64/lib/HCNetSDKCom
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
#   src/${PROJECT_NAME}/contNav.cpp
# )


#add_subdirectory(src/common)
#include_directories(./src/common)
#
#add_subdirectory(src/log)
#include_directories(./src/log)


# 查找所有cpp文件并将其存储在 SOURCES 变量中
file(GLOB SOURCES "src/*.cpp")

message("==============susuusu===============: ${SOURCES}")

# 创建可执行文件
add_executable(haikangdecte_node ${SOURCES})
add_dependencies(haikangdecte_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(haikangdecte_node  ${catkin_LIBRARIES}  ${OpenCV_LIBRARIES}
        #opencv_world
        #mysqlclient

#        analyzedata
#        AudioIntercom
#        HCAlarm
#        HCCoreDevCfg
#        HCDisplay
#        HCGeneralCfgMgr
#        HCIndustry
#        HCPlayBack
#        HCPreview
#        HCVoiceTalk
#        iconv2
#        StreamTransClient
#        SystemTransform
#
#
#
#        hcnetsdk
#        HCCore
#        AudioRender
#        crypto
#        hpr
#        NPQos
#        PlayCtrl
#        ssl
#        SuperRender
#        commonFun


        hcnetsdk
        HCCore
        AudioRender
        crypto
        hpr
        NPQos
        PlayCtrl
        ssl
        SuperRender

        analyzedata
        HCAlarm
        HCCoreDevCfg
        HCDisplay
        HCGeneralCfgMgr
        HCIndustry
        HCPlayBack
        HCPreview
        HCVoiceTalk
        iconv2
        StreamTransClient
        SystemTransform



        )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide src/sqlite/CppSQLite3.cpp
##========================test=============================================




##---






#add_executable(scan_to_pointcloud2_converter_node src/scan_to_pointcloud2_converter/scan_to_pointcloud2_converter.cpp )


## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against









#target_link_libraries(scan_to_pointcloud2_converter_node  ${catkin_LIBRARIES}   )



#####



## web ##


## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
#   scripts/my_python_script
#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_contNav.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

package.xml



  haikangdecte
  0.0.0
  The haikangdecte package

  
  
  
  sukai


  
  
  
  TODO


  
  
  
  


  
  
  
  


  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  
  catkin
  roscpp
  rosmsg
  rospy
  roscpp
  rosmsg
  rospy
  roscpp
  rosmsg
  rospy


  actionlib_msgs
  actionlib_msgs
  actionlib_msgs

  sensor_msgs
  sensor_msgs
  sensor_msgs

  geometry_msgs
  geometry_msgs
  geometry_msgs


  tf
  tf
  tf

  cv_bridge
  cv_bridge
  cv_bridge


  maindecte_msgs
  maindecte_msgs
  maindecte_msgs

  maindecte_srvs
  maindecte_srvs
  maindecte_srvs

  
  libpcl-all-dev
  libpcl-all-dev
  libpcl-all

  pcl_conversions
  pcl_conversions
  pcl_conversions

  pcl_ros
  pcl_ros
  pcl_ros

  std_srvs
  std_srvs
  std_srvs




  
  
    

  

配置 .bashrc
需要把SDK的lib目录加入到环境变量中,否则会报错:  error while loading shared libraries: libAudioRender.so: cannot open shared object file: No such file or directory
参考:
export LD_LIBRARY_PATH="/usr/lib/x86_64-linux-gnu:$LD_LIBRARY_PATH:/home/sukai/3rdparty/opencv4.5.0/build/install/lib:/usr/local/lib:/home/sukai/workspace/workspace_ros_car_noetic/src/haikangdecte/linux64/lib:/home/sukai/workspace/workspace_ros_car_noetic/src/haikangdecte/linux64:/home/sukai/workspace/workspace_ros_car_noetic/src/haikangdecte/linux64/lib/HCNetSDKCom"

消息格式:

msg消息:
maindecte_msgs/Msgdata
        string FilePath
        string filepath
        string OPT
        string task_id
        string sensor_id
        string x
        string y
        string dx
        string dy
        string resize_cotX
        string resize_cotY
        string msg
        string fPan
        string fTilt
        string fZoom
        string dwFocus
        string aperture
        string shutter
        string exposure
        string gain
        string data
        string CMD
        string Parameter
        string Direction
        string Speedlevel

---
srv消息:
    maindecte_srvs/maindecte
    int32 msgtype
    maindecte_msgs/Msgdata msgdata
    int32 dwPTZCommand
    int32 dwStop
    int32 dwSpeed
    ---
    string result
    string message
    maindecte_msgs/Msgdata result_msgdata
rqt 调试
rosrun rqt_service_caller rqt_service_caller

rosrun rqt_service_caller rqt_service_caller

启动:

rosrun haikangdecte haikangdecte_node

更详细请移步b站详细教程:昵称 再遇当年

开源地址:

https://gitee.com/yongwangzhiqiankai/haikangdecte.git

你可能感兴趣的:(ros,海康威视,热成像双光谱,MINI云台摄像,云台摄像改ros驱动,DS-2TD5567T-7/W)