ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Publishing camera_info messages

asked 2015-06-13 12:43:45 -0500

Diego gravatar image

Hello everyone

I am using Ubuntu 14.04 and Ros Indigo. I am trying to make the tutorial on camera_calibration ( http://wiki.ros.org/camera_calibratio... ) To do this they ask me to have these 2 topics publishing data:

/camera/camera_info

/camera/image_raw

I was using the image_transport_tutorials publisher video ( http://wiki.ros.org/image_transport/T... ) Additional to this, from this question http://answers.ros.org/question/11361... I added 4 lines and my program is publishing camera info, however I always receive this message

('Waiting for service', '/camera/set_camera_info', '...') Service not found

I will copy here the image_transport_tutorials publisher used... Could someone please tell me how can I make this code to publish camera information? (or how to publish information about the camera I am using)

 #include <ros/ros.h>
 #include <image_transport/image_transport.h>
 #include <opencv2/highgui/highgui.hpp>
 #include <cv_bridge/cv_bridge.h>
 #include <sstream> // for converting the command line parameter to integer

 int main(int argc, char** argv)
 {
 // Check if video source has been passed as a parameter
 if(argv[1] == NULL) return 1;

ros::init(argc, argv, "image_publisher");
ros::NodeHandle nh;
image_transport::ImageTransport it(nh);
image_transport::Publisher pub = it.advertise("camera/image", 1);
ros::Publisher pub_info_camera = nh.advertise<sensor_msgs::CameraInfo>("camera/camera_info", 1); //
sensor_msgs::CameraInfo info_camera; //

// Convert the passed as command line parameter index for the video device to an integer
std::istringstream video_sourceCmd(argv[1]);
int video_source;
// Check if it is indeed a number
if(!(video_sourceCmd >> video_source)) return 1;

cv::VideoCapture cap(video_source);
// Check if video device can be opened with the given index
if(!cap.isOpened()) return 1;
cv::Mat frame;
sensor_msgs::ImagePtr msg;

ros::Rate loop_rate(5);
while (nh.ok()) {
  cap >> frame;
  // Check if grabbed frame is actually full with some content
  if(!frame.empty()) {
    msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();
    info_camera.header.stamp = ros::Time::now(); //
    pub_info_camera.publish(info_camera); //
    pub.publish(msg);
    cv::waitKey(1);
  }

  ros::spinOnce();
  loop_rate.sleep();
}
}

Thanks in advance.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-11-02 07:21:17 -0500

Farid gravatar image

I managed to fix this problem with the following code:

you also need to have camera calibrated info saved in the YAML file in your computer.

#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
#include <camera_info_manager/camera_info_manager.h>
#include <sstream> 

using namespace std;
using namespace cv;
using namespace ros;

int main(int argc, char** argv)
{
  // Check if video source has been passed as a parameter

  init(argc, argv, "cameraPub");
  NodeHandle nh;



  string camera_name = "logitech_B525";
  image_transport::ImageTransport it(nh);
  image_transport::Publisher pub_cam_msg = it.advertise(camera_name+"/image_raw", 1);
  Publisher pub_cam_info = nh.advertise<sensor_msgs::CameraInfo>(camera_name+"/camera_info", 1);

  const string vsa = "http://192.168.43.26:8080/video?x.mjpeg";

 // IP webcam
// VideoCapture cap(vsa);
  VideoCapture cap(0);

  // Check video is open
  if (!cap.isOpened())
  {
    cerr<<"Could not open video!!"<<endl;
    nh.shutdown();
    return 1;
  }
  cout << "Camera: ON ------------>>>>>>>>>>>>" << endl;

  Mat frame;

  sensor_msgs::ImagePtr cam_msg;


  const string camurl = "file:///home/farid/WS_Farid/orb_slam2_TUT/settingFiles/logitech_B525.yaml";

  camera_info_manager::CameraInfoManager caminfo(nh, camera_name, camurl);

  sensor_msgs::CameraInfo ci;

  Rate loop_rate(5);

  while (nh.ok()) {

    cap >> frame;

    if(!frame.empty())
    {
        cam_msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();

        ci.header.stamp = ros::Time::now(); //
        ci=caminfo.getCameraInfo();

        pub_cam_msg.publish(cam_msg);
        pub_cam_info.publish(ci);

            //imshow("video stream",frame);
            waitKey(1); // 30 ms */
    }
    else
    {
    cout << "EMPTY FRAME!" << endl;
    }

    spinOnce();
    //loop_rate.sleep();
  }
  return 0;
}
edit flag offensive delete link more
0

answered 2016-01-24 03:12:39 -0500

Azharudeen gravatar image

just use camera_info_manager

set the name of nodehandler appropriately after inspecting the required service name{in your case it is camera/image}

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-06-13 12:43:45 -0500

Seen: 4,982 times

Last updated: Nov 02 '18