image_publisher_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, JSK Lab.
5 * 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 #include <ros/ros.h>
37 #include <nodelet/nodelet.h>
38 #include <cv_bridge/cv_bridge.h>
39 #include <image_publisher/ImagePublisherConfig.h>
41 #include <sensor_msgs/CameraInfo.h>
43 #include <opencv2/highgui/highgui.hpp>
44 #include <dynamic_reconfigure/server.h>
45 #include <boost/assign.hpp>
46 using namespace boost::assign;
47 
48 namespace image_publisher {
50 {
51  typedef dynamic_reconfigure::Server<image_publisher::ImagePublisherConfig> ReconfigureServer;
53 
55 
58 
59  cv::VideoCapture cap_;
60  cv::Mat image_;
63 
64  std::string frame_id_;
65  std::string filename_;
68  sensor_msgs::CameraInfo camera_info_;
69 
70 
71  void reconfigureCallback(image_publisher::ImagePublisherConfig &new_config, uint32_t level)
72  {
73  frame_id_ = new_config.frame_id;
74 
75  timer_ = nh_.createTimer(ros::Duration(1.0/new_config.publish_rate), &ImagePublisherNodelet::do_work, this);
76 
78  if ( !new_config.camera_info_url.empty() ) {
79  try {
80  c.validateURL(new_config.camera_info_url);
81  c.loadCameraInfo(new_config.camera_info_url);
82  camera_info_ = c.getCameraInfo();
83  } catch(cv::Exception &e) {
84  NODELET_ERROR("camera calibration failed to load: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
85  }
86  }
87 
88 
89  }
90 
91  void do_work(const ros::TimerEvent& event)
92  {
93  // Transform the image.
94  try
95  {
96  if ( cap_.isOpened() ) {
97  if ( ! cap_.read(image_) ) {
98  cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
99  }
100  }
101  if (flip_image_)
102  cv::flip(image_, image_, flip_value_);
103 
104  sensor_msgs::ImagePtr out_img = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_).toImageMsg();
105  out_img->header.frame_id = frame_id_;
106  out_img->header.stamp = ros::Time::now();
107  camera_info_.header.frame_id = out_img->header.frame_id;
108  camera_info_.header.stamp = out_img->header.stamp;
109 
110  pub_.publish(*out_img, camera_info_);
111  }
112  catch (cv::Exception &e)
113  {
114  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
115  }
116  }
117 
119  {
120  subscriber_count_++;
121  }
122 
124  {
125  subscriber_count_--;
126  }
127 
128 public:
129  virtual void onInit()
130  {
131  subscriber_count_ = 0;
132  nh_ = getPrivateNodeHandle();
134  pub_ = image_transport::ImageTransport(nh_).advertiseCamera("image_raw", 1);
135 
136  nh_.param("filename", filename_, std::string(""));
137  NODELET_INFO("File name for publishing image is : %s", filename_.c_str());
138  try {
139  image_ = cv::imread(filename_, cv::IMREAD_COLOR);
140  if ( image_.empty() ) { // if filename is motion file or device file
141  try { // if filename is number
142  int num = boost::lexical_cast<int>(filename_);//num is 1234798797
143  cap_.open(num);
144  } catch(boost::bad_lexical_cast &) { // if file name is string
145  cap_.open(filename_);
146  }
147  CV_Assert(cap_.isOpened());
148  cap_.read(image_);
149  cap_.set(cv::CAP_PROP_POS_FRAMES, 0);
150  }
151  CV_Assert(!image_.empty());
152  }
153  catch (cv::Exception &e)
154  {
155  NODELET_ERROR("Failed to load image (%s): %s %s %s %i", filename_.c_str(), e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
156  }
157 
158  bool flip_horizontal;
159  nh_.param("flip_horizontal", flip_horizontal, false);
160  NODELET_INFO("Flip horizontal image is : %s", ((flip_horizontal)?"true":"false"));
161 
162  bool flip_vertical;
163  nh_.param("flip_vertical", flip_vertical, false);
164  NODELET_INFO("Flip flip_vertical image is : %s", ((flip_vertical)?"true":"false"));
165 
166  // From http://docs.opencv.org/modules/core/doc/operations_on_arrays.html#void flip(InputArray src, OutputArray dst, int flipCode)
167  // FLIP_HORIZONTAL == 1, FLIP_VERTICAL == 0 or FLIP_BOTH == -1
168  flip_image_ = true;
169  if (flip_horizontal && flip_vertical)
170  flip_value_ = 0; // flip both, horizontal and vertical
171  else if (flip_horizontal)
172  flip_value_ = 1;
173  else if (flip_vertical)
174  flip_value_ = -1;
175  else
176  flip_image_ = false;
177 
178  camera_info_.width = image_.cols;
179  camera_info_.height = image_.rows;
180  camera_info_.distortion_model = "plumb_bob";
181  camera_info_.D = list_of(0)(0)(0)(0)(0).convert_to_container<std::vector<double> >();
182  camera_info_.K = list_of(1)(0)(camera_info_.width/2)(0)(1)(camera_info_.height/2)(0)(0)(1);
183  camera_info_.R = list_of(1)(0)(0)(0)(1)(0)(0)(0)(1);
184  camera_info_.P = list_of(1)(0)(camera_info_.width/2)(0)(0)(1)(camera_info_.height/2)(0)(0)(0)(1)(0);
185 
186  timer_ = nh_.createTimer(ros::Duration(1), &ImagePublisherNodelet::do_work, this);
187 
188  srv.reset(new ReconfigureServer(getPrivateNodeHandle()));
189  ReconfigureServer::CallbackType f =
190  boost::bind(&ImagePublisherNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
191  srv->setCallback(f);
192  }
193 };
194 }
image_publisher::ImagePublisherNodelet::connectCb
void connectCb(const image_transport::SingleSubscriberPublisher &ssp)
Definition: image_publisher_nodelet.cpp:118
NODELET_ERROR
#define NODELET_ERROR(...)
camera_info_manager::CameraInfoManager::getCameraInfo
virtual sensor_msgs::CameraInfo getCameraInfo(void)
image_transport::ImageTransport
boost::shared_ptr< ReconfigureServer >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ros.h
image_publisher::ImagePublisherNodelet::disconnectCb
void disconnectCb(const image_transport::SingleSubscriberPublisher &)
Definition: image_publisher_nodelet.cpp:123
image_publisher::ImagePublisherNodelet::onInit
virtual void onInit()
Definition: image_publisher_nodelet.cpp:129
image_publisher::ImagePublisherNodelet::frame_id_
std::string frame_id_
Definition: image_publisher_nodelet.cpp:64
image_publisher::ImagePublisherNodelet::filename_
std::string filename_
Definition: image_publisher_nodelet.cpp:65
image_publisher::ImagePublisherNodelet::timer_
ros::Timer timer_
Definition: image_publisher_nodelet.cpp:62
image_publisher::ImagePublisherNodelet
Definition: image_publisher_nodelet.cpp:49
image_publisher::ImagePublisherNodelet::subscriber_count_
int subscriber_count_
Definition: image_publisher_nodelet.cpp:61
camera_info_manager.h
image_publisher::ImagePublisherNodelet::nh_
ros::NodeHandle nh_
Definition: image_publisher_nodelet.cpp:57
camera_info_manager::CameraInfoManager::loadCameraInfo
virtual bool loadCameraInfo(const std::string &url)
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
image_publisher::ImagePublisherNodelet::flip_image_
bool flip_image_
Definition: image_publisher_nodelet.cpp:66
image_publisher::ImagePublisherNodelet::ReconfigureServer
dynamic_reconfigure::Server< image_publisher::ImagePublisherConfig > ReconfigureServer
Definition: image_publisher_nodelet.cpp:51
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
f
f
image_publisher::ImagePublisherNodelet::reconfigureCallback
void reconfigureCallback(image_publisher::ImagePublisherConfig &new_config, uint32_t level)
Definition: image_publisher_nodelet.cpp:71
image_publisher::ImagePublisherNodelet::image_
cv::Mat image_
Definition: image_publisher_nodelet.cpp:60
image_publisher::ImagePublisherNodelet::flip_value_
int flip_value_
Definition: image_publisher_nodelet.cpp:67
camera_info_manager::CameraInfoManager
image_transport::CameraPublisher
image_publisher::ImagePublisherNodelet::do_work
void do_work(const ros::TimerEvent &event)
Definition: image_publisher_nodelet.cpp:91
ros::TimerEvent
image_transport::SingleSubscriberPublisher
image_transport.h
image_publisher::ImagePublisherNodelet::pub_
image_transport::CameraPublisher pub_
Definition: image_publisher_nodelet.cpp:54
camera_info_manager::CameraInfoManager::validateURL
virtual bool validateURL(const std::string &url)
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
nodelet.h
cv_bridge.h
cv_bridge::CvImage
class_list_macros.hpp
image_publisher::ImagePublisherNodelet::camera_info_
sensor_msgs::CameraInfo camera_info_
Definition: image_publisher_nodelet.cpp:68
image_publisher::ImagePublisherNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: image_publisher_nodelet.cpp:56
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
image_publisher
Definition: image_publisher_nodelet.cpp:48
image_publisher::ImagePublisherNodelet::srv
boost::shared_ptr< ReconfigureServer > srv
Definition: image_publisher_nodelet.cpp:52
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(image_publisher::ImagePublisherNodelet, nodelet::Nodelet)
image_publisher::ImagePublisherNodelet::cap_
cv::VideoCapture cap_
Definition: image_publisher_nodelet.cpp:59
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ros::NodeHandle
ros::Time::now
static Time now()


image_publisher
Author(s): Kei Okada
autogenerated on Wed Jan 24 2024 03:57:19