image_pub_nodelet.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <algorithm>
00031 
00032 #include <boost/make_shared.hpp>
00033 
00034 #include <cv_bridge/cv_bridge.h>
00035 #include <image_transport/image_transport.h>
00036 #include <image_transport/publisher.h>
00037 #include <image_transport/subscriber.h>
00038 #include <opencv2/core/core.hpp>
00039 #include <opencv2/highgui/highgui.hpp>
00040 #include <nodelet/nodelet.h>
00041 #include <ros/ros.h>
00042 #include <sensor_msgs/Image.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 #include <swri_roscpp/parameters.h>
00045 
00046 namespace swri_image_util
00047 {
00048   class ImagePubNodelet : public nodelet::Nodelet
00049   {
00050     public:
00051       virtual void onInit()
00052       {
00053         ros::NodeHandle node = getNodeHandle();
00054 
00055         init_timer_ = node.createTimer(
00056             ros::Duration(1.0), &ImagePubNodelet::initialize, this, true);
00057       }
00058 
00059       void initialize(const ros::TimerEvent& unused)
00060       {
00061         ros::NodeHandle &node = getNodeHandle();
00062         ros::NodeHandle &priv = getPrivateNodeHandle();
00063 
00064         std::string image_file;
00065         swri::param(priv, "image_file", image_file, image_file);
00066 
00067         std::string mode;
00068         swri::param(priv, "mode", mode, sensor_msgs::image_encodings::BGR8);
00069 
00070         double rate = 1;
00071         swri::param(priv, "rate", rate, rate);
00072         rate = std::max(0.1, rate);
00073 
00074         cv_image.header.stamp = ros::Time::now();
00075         if (mode == sensor_msgs::image_encodings::BGR8)
00076         {
00077           cv_image.image = cv::imread(image_file, CV_LOAD_IMAGE_COLOR);
00078           cv_image.encoding = sensor_msgs::image_encodings::BGR8;
00079         }
00080         else
00081         {
00082           cv_image.image = cv::imread(image_file, CV_LOAD_IMAGE_GRAYSCALE);
00083           cv_image.encoding = sensor_msgs::image_encodings::MONO8;
00084         }
00085 
00086         if (!cv_image.image.empty())
00087         {
00088           image_transport::ImageTransport it(node);
00089           image_pub_ = it.advertise("image", 2, true);
00090           pub_timer_ = node.createTimer(
00091               ros::Duration(1.0 / rate), &ImagePubNodelet::publish, this);
00092         }
00093         else
00094         {
00095           ROS_FATAL("Failed to load image.");
00096           ros::requestShutdown();
00097         }
00098       }
00099 
00100       void publish(const ros::TimerEvent& e)
00101       {
00102         cv_image.header.stamp = e.current_real;
00103         image_pub_.publish(cv_image.toImageMsg());
00104       }
00105 
00106     private:
00107       ros::Timer init_timer_;
00108       ros::Timer pub_timer_;
00109       image_transport::Publisher image_pub_;
00110 
00111       cv_bridge::CvImage cv_image;
00112   };
00113 }
00114 
00115 // Register nodelet plugin
00116 #include <swri_nodelet/class_list_macros.h>
00117 SWRI_NODELET_EXPORT_CLASS(swri_image_util, ImagePubNodelet)


swri_image_util
Author(s): Kris Kozak
autogenerated on Thu Jun 6 2019 20:34:52