rotate_image_nodelet.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2014, 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 <string>
31 
32 #include <opencv2/core/core.hpp>
33 
34 #include <ros/ros.h>
35 #include <nodelet/nodelet.h>
38 #include <sensor_msgs/Image.h>
39 #include <cv_bridge/cv_bridge.h>
40 
42 
43 namespace swri_image_util
44 {
46  {
47  public:
49  angle_(0),
50  operations_(0),
51  flip_axis_(false)
52  {
53  }
54 
56  {
57  }
58 
59  void onInit()
60  {
63 
64  priv.param("angle", angle_, angle_);
65 
66  int32_t angle_90 = static_cast<int32_t>(swri_math_util::ToNearest(angle_, 90));
67  flip_axis_ = angle_90 > 0 ? 1 : 0;
68  operations_ = std::abs(angle_90 / 90);
69 
71  image_pub_ = it.advertise("rotated_image", 1);
73  }
74 
75  void ImageCallback(const sensor_msgs::ImageConstPtr& image)
76  {
77  if (operations_ == 0)
78  {
79  image_pub_.publish(image);
80  return;
81  }
82 
84 
85  for (int32_t i = 0; i < operations_; i++)
86  {
87  cv::transpose(cv_image->image, cv_image->image);
88  cv::flip(cv_image->image, cv_image->image, flip_axis_);
89  }
90 
91  image_pub_.publish(cv_image->toImageMsg());
92  }
93 
94  private:
95  double angle_;
96  int32_t operations_;
97  bool flip_axis_;
98 
101 
102  };
103 }
104 
105 // Register nodelet plugin
107 SWRI_NODELET_EXPORT_CLASS(swri_image_util, RotateImageNodelet)
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
boost::shared_ptr
swri_image_util::RotateImageNodelet::onInit
void onInit()
Definition: rotate_image_nodelet.cpp:59
ros.h
swri_image_util
Definition: draw_util.h:37
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber
class_list_macros.h
swri_image_util::RotateImageNodelet::image_sub_
image_transport::Subscriber image_sub_
Definition: rotate_image_nodelet.cpp:99
swri_image_util::RotateImageNodelet::operations_
int32_t operations_
Definition: rotate_image_nodelet.cpp:96
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
swri_image_util::RotateImageNodelet::image_pub_
image_transport::Publisher image_pub_
Definition: rotate_image_nodelet.cpp:100
swri_image_util::RotateImageNodelet::flip_axis_
bool flip_axis_
Definition: rotate_image_nodelet.cpp:97
swri_image_util::RotateImageNodelet::ImageCallback
void ImageCallback(const sensor_msgs::ImageConstPtr &image)
Definition: rotate_image_nodelet.cpp:75
swri_image_util::RotateImageNodelet::~RotateImageNodelet
~RotateImageNodelet()
Definition: rotate_image_nodelet.cpp:55
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
swri_image_util::RotateImageNodelet
Definition: rotate_image_nodelet.cpp:45
math_util.h
image_transport.h
nodelet::Nodelet
nodelet.h
image_transport::Publisher
cv_bridge.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
swri_math_util::ToNearest
double ToNearest(double value, double multiple)
swri_image_util::RotateImageNodelet::angle_
double angle_
Definition: rotate_image_nodelet.cpp:95
swri_image_util::RotateImageNodelet::RotateImageNodelet
RotateImageNodelet()
Definition: rotate_image_nodelet.cpp:48
ros::NodeHandle


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