image_pub_nodelet.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
30 #include <algorithm>
31 
32 #include <boost/make_shared.hpp>
33 
34 #include <cv_bridge/cv_bridge.h>
38 #include <opencv2/core/core.hpp>
39 #include <opencv2/highgui/highgui.hpp>
40 #include <nodelet/nodelet.h>
41 #include <ros/ros.h>
42 #include <sensor_msgs/Image.h>
44 #include <swri_roscpp/parameters.h>
45 
46 namespace swri_image_util
47 {
49  {
50  public:
51  virtual void onInit()
52  {
54 
55  init_timer_ = node.createTimer(
56  ros::Duration(1.0), &ImagePubNodelet::initialize, this, true);
57  }
58 
59  void initialize(const ros::TimerEvent& unused)
60  {
63 
64  std::string image_file;
65  swri::param(priv, "image_file", image_file, image_file);
66 
67  std::string mode;
69 
70  double rate = 1;
71  swri::param(priv, "rate", rate, rate);
72  rate = std::max(0.1, rate);
73 
74  cv_image.header.stamp = ros::Time::now();
76  {
77  cv_image.image = cv::imread(image_file, cv::IMREAD_COLOR);
79  }
80  else
81  {
82  cv_image.image = cv::imread(image_file, cv::IMREAD_GRAYSCALE);
84  }
85 
86  if (!cv_image.image.empty())
87  {
89  image_pub_ = it.advertise("image", 2, true);
90  pub_timer_ = node.createTimer(
91  ros::Duration(1.0 / rate), &ImagePubNodelet::publish, this);
92  }
93  else
94  {
95  ROS_FATAL("Failed to load image.");
97  }
98  }
99 
100  void publish(const ros::TimerEvent& e)
101  {
102  cv_image.header.stamp = e.current_real;
104  }
105 
106  private:
110 
112  };
113 }
114 
115 // Register nodelet plugin
swri_image_util::ImagePubNodelet
Definition: image_pub_nodelet.cpp:48
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
SWRI_NODELET_EXPORT_CLASS
SWRI_NODELET_EXPORT_CLASS(swri_image_util, DrawPolygonNodelet)
image_transport::ImageTransport
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ros.h
swri_image_util::ImagePubNodelet::image_pub_
image_transport::Publisher image_pub_
Definition: image_pub_nodelet.cpp:109
swri_image_util
Definition: draw_util.h:37
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::requestShutdown
ROSCPP_DECL void requestShutdown()
publisher.h
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
class_list_macros.h
swri_image_util::ImagePubNodelet::initialize
void initialize(const ros::TimerEvent &unused)
Definition: image_pub_nodelet.cpp:59
swri_image_util::ImagePubNodelet::pub_timer_
ros::Timer pub_timer_
Definition: image_pub_nodelet.cpp:108
cv_bridge::CvImage::header
std_msgs::Header header
subscriber.h
parameters.h
swri_image_util::ImagePubNodelet::init_timer_
ros::Timer init_timer_
Definition: image_pub_nodelet.cpp:107
ros::TimerEvent
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
ros::TimerEvent::current_real
Time current_real
ROS_FATAL
#define ROS_FATAL(...)
image_transport.h
swri_image_util::ImagePubNodelet::cv_image
cv_bridge::CvImage cv_image
Definition: image_pub_nodelet.cpp:111
nodelet::Nodelet
cv_bridge::CvImage::encoding
std::string encoding
nodelet.h
image_transport::Publisher
sensor_msgs::image_encodings::MONO8
const std::string MONO8
cv_bridge.h
cv_bridge::CvImage
swri_image_util::ImagePubNodelet::onInit
virtual void onInit()
Definition: image_pub_nodelet.cpp:51
sensor_msgs::image_encodings::BGR8
const std::string BGR8
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
cv_bridge::CvImage::image
cv::Mat image
ros::Duration
ros::Timer
swri_image_util::ImagePubNodelet::publish
void publish(const ros::TimerEvent &e)
Definition: image_pub_nodelet.cpp:100
swri::param
static void param(const ros::NodeHandle &nh, const std::string &name, bool &variable, const bool default_value)
ros::NodeHandle
ros::Time::now
static Time now()


swri_image_util
Author(s): Kris Kozak
autogenerated on Thu Jun 6 2024 02:33:12