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

how to publish sensor_msgs::CameraInfo messages ?

asked 2011-09-29 01:44:31 -0500

updated 2011-10-04 04:13:19 -0500

joq gravatar image

I am unable to publish the CameraInfo messages. I have the image data published from the camera using the image_transport::Publisher but the same is not publishing the camera info messages.

I am writing a driver for the ueye camera. I need the camera info message for calibration of the camera. I am able to detect the corners in the chessboard but then the program hangs after completion may be because it could not find the camera info messages containing the camera model.

edit retag flag offensive close merge delete

Comments

I think this link might answer your question.

Farid gravatar image Farid  ( 2018-11-02 07:24:15 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
3

answered 2011-09-29 03:20:17 -0500

joq gravatar image

The recommended method is to use image_transport and camera_info_manager.

Here's how camera1394 does it:

  /** Publish camera stream topics
   *
   *  @param image points to latest camera frame
   */
  void Camera1394Driver::publish(const sensor_msgs::ImagePtr &image)
  {
    image->header.frame_id = config_.frame_id;

    // get current CameraInfo data
    sensor_msgs::CameraInfoPtr
      ci(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));

    // check whether CameraInfo matches current video mode
    if (!dev_->checkCameraInfo(*image, *ci))
      {
        // image size does not match: publish a matching uncalibrated
        // CameraInfo instead
        if (calibration_matches_)
          {
            // warn user once
            calibration_matches_ = false;
            ROS_WARN_STREAM("[" << camera_name_
                            << "] calibration does not match video mode "
                            << "(publishing uncalibrated data)");
          }
        ci.reset(new sensor_msgs::CameraInfo());
        ci->height = image->height;
        ci->width = image->width;
      }
    else if (!calibration_matches_)
      {
        // calibration OK now
        calibration_matches_ = true;
        ROS_WARN_STREAM("[" << camera_name_
                        << "] calibration matches video mode now");
      }

    // fill in operational parameters
    dev_->setOperationalParameters(*ci);

    ci->header.frame_id = config_.frame_id;
    ci->header.stamp = image->header.stamp;

    // @todo log a warning if (filtered) time since last published
    // image is not reasonably close to configured frame_rate

    // Publish via image_transport
    image_pub_.publish(image, ci);
  }
edit flag offensive delete link more
1

answered 2011-09-29 02:45:03 -0500

Thomas D gravatar image

Declare your publisher, I do this in main:

ros::Publisher pub_info_left = nh.advertise<sensor_msgs::CameraInfo>("left/camera_info", 1);
sensor_msgs::CameraInfo info_left;

Then, in a callback function or in a while() loop in main do this:

info_left.header.stamp = ros::Time::now();
pub_info_left.publish(info_left);

I have implemented this in an approximate time synchronization node where I subscribe to the image and info topics from two different cameras, set all of their timestamps equal to each other then republish on those four topics here. That would be a more complete code example if the one above is not clear enough.

edit flag offensive delete link more

Comments

1
@joq's answer is better than this one, not least because it is the recommended method and we should be trying to do things in a standard way.
Thomas D gravatar image Thomas D  ( 2011-09-29 03:29:56 -0500 )edit

To add to Thomas D's comment, another way to do this would be using message_filters::TimeSynchronizer, set up to subscribe to each camera

TimboInSpace gravatar image TimboInSpace  ( 2014-12-15 12:23:34 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2011-09-29 01:44:31 -0500

Seen: 16,524 times

Last updated: Sep 29 '11