Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <string>
00031
00032 #include <opencv2/core/core.hpp>
00033
00034 #include <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <sensor_msgs/Image.h>
00039 #include <cv_bridge/cv_bridge.h>
00040
00041 #include <swri_math_util/math_util.h>
00042
00043 namespace swri_image_util
00044 {
00045 class RotateImageNodelet : public nodelet::Nodelet
00046 {
00047 public:
00048 RotateImageNodelet() :
00049 angle_(0),
00050 operations_(0),
00051 flip_axis_(false)
00052 {
00053 }
00054
00055 ~RotateImageNodelet()
00056 {
00057 }
00058
00059 void onInit()
00060 {
00061 ros::NodeHandle &node = getNodeHandle();
00062 ros::NodeHandle &priv = getPrivateNodeHandle();
00063
00064 priv.param("angle", angle_, angle_);
00065
00066 int32_t angle_90 = static_cast<int32_t>(swri_math_util::ToNearest(angle_, 90));
00067 flip_axis_ = angle_90 > 0 ? 1 : 0;
00068 operations_ = std::abs(angle_90 / 90);
00069
00070 image_transport::ImageTransport it(node);
00071 image_pub_ = it.advertise("rotated_image", 1);
00072 image_sub_ = it.subscribe("image", 1, &RotateImageNodelet::ImageCallback, this);
00073 }
00074
00075 void ImageCallback(const sensor_msgs::ImageConstPtr& image)
00076 {
00077 if (operations_ == 0)
00078 {
00079 image_pub_.publish(image);
00080 return;
00081 }
00082
00083 cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image);
00084
00085 for (int32_t i = 0; i < operations_; i++)
00086 {
00087 cv::transpose(cv_image->image, cv_image->image);
00088 cv::flip(cv_image->image, cv_image->image, flip_axis_);
00089 }
00090
00091 image_pub_.publish(cv_image->toImageMsg());
00092 }
00093
00094 private:
00095 double angle_;
00096 int32_t operations_;
00097 bool flip_axis_;
00098
00099 image_transport::Subscriber image_sub_;
00100 image_transport::Publisher image_pub_;
00101
00102 };
00103 }
00104
00105
00106 #include <swri_nodelet/class_list_macros.h>
00107 SWRI_NODELET_EXPORT_CLASS(swri_image_util, RotateImageNodelet)