在ROS中输出小觅相机的曝光信息

设备:小觅相机标准班 S1030-IR

SDK版本:2.3.4

1.在launch文件中添加话题信息

打开    MYNT-EYE-S-SDK/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch

(1)在

 

 

下方加入

 

设置输出曝光时间的Publisher变量为 exposure_time_topic,发布的话题名称设置为 exposure_time

(2)在


   

     

下方加入

2.修改源文件 wrapper_nodelet.cc

(1)添加所需头文件

//add for getting exposure time 
#include "mynteye/device/utils.h"
#include 

(2)在 onInit() 函数中添加如下代码,将曝光时间的话题信息传递给系统

    std::string exposure_time_topic = "exposure_time";
    private_nh_.getParam("exposure_time_topic", exposure_time_topic);

可以添加在“private_nh_.getParam("base_frame_id", base_frame_id_);”下方

(3)修改 publishCamera 函数

  void publishCamera(
      const Stream &stream, const api::StreamData &data, std::uint32_t seq,
      ros::Time stamp) {

    // if (camera_publishers_[stream].getNumSubscribers() == 0)
    //   return;
    std_msgs::Header header;
    header.seq = seq;
    header.stamp = stamp;
    header.frame_id = frame_ids_[stream];
    pthread_mutex_lock(&mutex_data_);
    cv::Mat img = data.frame;//Mao:data.frame => img => msg => publisher
    
    //调用get_real_exposure_time函数,计算得到真正的曝光时间(单位为ms)
    //参照相机自带的例程 auto_exposure.cc , 该例程调用 CVPainter 在图像上显示曝光时间
    // cv_painter.cc 中定义的 CVPainter::DrawImgData, 调用get_real_exposure_time来获取曝光时间
    std::float_t exposure_time;
    if (frame_rate_ == 0) {
	exposure_time = data.img->exposure_time;
    }
    else{
	exposure_time = utils::get_real_exposure_time(
                          frame_rate_, data.img->exposure_time);
    }
    
    if (stream == Stream::DISPARITY) {  // 32FC1 > 8UC1 = MONO8
      img.convertTo(img, CV_8UC1);
    }
    //Trans "img" to ROS type
    auto &&msg =
        cv_bridge::CvImage(header, camera_encodings_[stream], img).toImageMsg();    

    //在终端输出曝光时间
    //ROS_INFO("exposure_time is  %f",exposure_time);
    
    pthread_mutex_unlock(&mutex_data_);
    auto &&info = getCameraInfo(stream);
    info->header.stamp = msg->header.stamp;
    //Mao:publish exposure time
    ROS_INFO("Header seq is  %d",header.seq);
    //ROS_INFO("Header time is  %f",header.time.toSec());
    
    //if(header.frame_id == "mynteye_left_frame") out<<"Img header: "<

(4)(可选)使相机在没有节点订阅 exposure_time 话题的情况下,能够输出曝光时间

上述方法在运行 display.launch 时,可以输出曝光时间;

在运行mynteye.launch时,只在有节点订阅图像信息时,能够伴随输出(没有节点订阅时,系统会不指定publishCamera)

为了使相机可以运行即发布图像信息和曝光信息,可以将 publishTopics() 函数中的判断条件

if ((camera_publishers_[Stream::LEFT].getNumSubscribers() > 0 ||
        mono_publishers_[Stream::LEFT].getNumSubscribers() > 0) &&
        !is_published_[Stream::LEFT]) 

修改为

if(1)

3.测试

(1)使用display.launch启动相机

cd MYNT-EYE-S-SDK-2.3.4
source wrappers/ros/devel/setup.bash
roslaunch mynt_eye_ros_wrapper display.launch

(2)订阅 exposure_topic 话题

rostopic echo /mynteye/exposure_time

也可以

(1)使用mynteye.launch启动相机

(2)(按照2.(4)修改后则跳过)打开某个SLAM算法订阅图像信息,或者运行以下代码订阅图片信息

rostopic echo /mynteye/left/image_raw

(3)订阅 exposure_topic 话题

rostopic echo /mynteye/exposure_time

PS:感谢小觅售后的耐心解答

你可能感兴趣的:(C++,ROS)