00001 #include <ros/ros.h>
00002 #include <tf/transform_listener.h>
00003 #include <tf/transform_broadcaster.h>
00004 #include <image_rotate/ImageRotateConfig.h>
00005 #include <geometry_msgs/Vector3Stamped.h>
00006 #include <image_transport/image_transport.h>
00007 #include <cv_bridge/CvBridge.h>
00008 #include <dynamic_reconfigure/server.h>
00009 #include <math.h>
00010
00011 class ImageRotater
00012 {
00013 tf::TransformListener tf_sub_;
00014 tf::TransformBroadcaster tf_pub_;
00015
00016 image_rotate::ImageRotateConfig config_;
00017 dynamic_reconfigure::Server<image_rotate::ImageRotateConfig> srv;
00018
00019 image_transport::Publisher img_pub_;
00020 image_transport::Subscriber img_sub_;
00021 image_transport::CameraSubscriber cam_sub_;
00022
00023 sensor_msgs::CvBridge bridge_;
00024
00025 tf::Stamped<tf::Vector3> target_vector_;
00026 tf::Stamped<tf::Vector3> source_vector_;
00027
00028 image_transport::ImageTransport it_;
00029 ros::NodeHandle nh_;
00030
00031 int subscriber_count_;
00032 double angle_;
00033 ros::Time prev_stamp_;
00034
00035 void reconfigureCallback(image_rotate::ImageRotateConfig &new_config, uint32_t level)
00036 {
00037 config_ = new_config;
00038 target_vector_.setValue(config_.target_x, config_.target_y, config_.target_z);
00039 source_vector_.setValue(config_.source_x, config_.source_y, config_.source_z);
00040 if (subscriber_count_)
00041 {
00042 unsubscribe();
00043 subscribe();
00044 }
00045 }
00046
00047 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00048 {
00049 if (frame.empty())
00050 return image_frame;
00051 return frame;
00052 }
00053
00054 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00055 {
00056 do_work(msg, cam_info->header.frame_id);
00057 }
00058
00059 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00060 {
00061 do_work(msg, msg->header.frame_id);
00062 }
00063
00064 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00065 {
00066 try
00067 {
00068 std::string input_frame_id = frameWithDefault(config_.input_frame_id, input_frame_from_msg);
00069
00070
00071 target_vector_.stamp_ = msg->header.stamp;
00072 target_vector_.frame_id_ = frameWithDefault(config_.target_frame_id, input_frame_id);
00073 tf::Stamped<tf::Vector3> target_vector_transformed;
00074 tf_sub_.waitForTransform(input_frame_id, msg->header.stamp,
00075 target_vector_.frame_id_, target_vector_.stamp_,
00076 input_frame_id, ros::Duration(0.2));
00077 tf_sub_.transformVector(input_frame_id, msg->header.stamp, target_vector_,
00078 input_frame_id, target_vector_transformed);
00079
00080
00081 source_vector_.stamp_ = msg->header.stamp;
00082 source_vector_.frame_id_ = frameWithDefault(config_.source_frame_id, input_frame_id);
00083 tf::Stamped<tf::Vector3> source_vector_transformed;
00084 tf_sub_.waitForTransform(input_frame_id, msg->header.stamp,
00085 source_vector_.frame_id_, source_vector_.stamp_,
00086 input_frame_id, ros::Duration(0.01));
00087 tf_sub_.transformVector(input_frame_id, msg->header.stamp, source_vector_,
00088 input_frame_id, source_vector_transformed);
00089
00090
00091
00092
00093
00094
00095
00096 double angle = angle_;
00097 if ((target_vector_transformed.x() != 0 || target_vector_transformed.y() != 0) &&
00098 (source_vector_transformed.x() != 0 || source_vector_transformed.y() != 0))
00099 {
00100 angle = atan2(target_vector_transformed.y(), target_vector_transformed.x());
00101 angle -= atan2(source_vector_transformed.y(), source_vector_transformed.x());
00102 }
00103
00104
00105 if (config_.max_angular_rate == 0)
00106 angle_ = angle;
00107 else
00108 {
00109 double delta = fmod(angle - angle_, 2.0 * M_PI);
00110 if (delta > M_PI)
00111 delta -= 2.0 * M_PI;
00112 else if (delta < - M_PI)
00113 delta += 2.0 * M_PI;
00114
00115 double max_delta = config_.max_angular_rate * (msg->header.stamp - prev_stamp_).toSec();
00116 if (delta > max_delta)
00117 delta = max_delta;
00118 else if (delta < -max_delta)
00119 delta = - max_delta;
00120
00121 angle_ += delta;
00122 }
00123 angle_ = fmod(angle_, 2.0 * M_PI);
00124 }
00125 catch (tf::TransformException &e)
00126 {
00127 ROS_ERROR("Transform error: %s", e.what());
00128 }
00129
00130
00131
00132
00133 tf::StampedTransform transform;
00134 transform.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00135 transform.setRotation(tf::Quaternion(tf::Vector3(0.0, 0.0, 1.0), angle_));
00136 transform.frame_id_ = msg->header.frame_id;
00137 transform.child_frame_id_ = frameWithDefault(config_.output_frame_id, msg->header.frame_id + "_rotated");
00138 transform.stamp_ = msg->header.stamp;
00139 tf_pub_.sendTransform(transform);
00140
00141
00142 try
00143 {
00144
00145 IplImage *in_image_ipl = bridge_.imgMsgToCv(msg, "passthrough");
00146 cv::Mat in_image = in_image_ipl;
00147
00148
00149 int max_dim = in_image.cols > in_image.rows ? in_image.cols : in_image.rows;
00150 int min_dim = in_image.cols < in_image.rows ? in_image.cols : in_image.rows;
00151 int noblack_dim = min_dim / sqrt(2);
00152 int diag_dim = sqrt(in_image.cols*in_image.cols + in_image.rows*in_image.rows);
00153 int out_size;
00154 int candidates[] = { noblack_dim, min_dim, max_dim, diag_dim, diag_dim };
00155 int step = config_.output_image_size;
00156 out_size = candidates[step] + (candidates[step + 1] - candidates[step]) * (config_.output_image_size - step);
00157
00158
00159
00160 cv::Mat rot_matrix = cv::getRotationMatrix2D(cv::Point2f(in_image.cols / 2.0, in_image.rows / 2.0), 180 * angle_ / M_PI, 1);
00161 cv::Mat translation = rot_matrix.col(2);
00162 rot_matrix.at<double>(0, 2) += (out_size - in_image.cols) / 2.0;
00163 rot_matrix.at<double>(1, 2) += (out_size - in_image.rows) / 2.0;
00164
00165
00166 cv::Mat out_image;
00167 cv::warpAffine(in_image, out_image, rot_matrix, cv::Size(out_size, out_size));
00168
00169
00170 IplImage out_msg = out_image;
00171 sensor_msgs::Image::Ptr out_img = bridge_.cvToImgMsg(&out_msg, msg->encoding);
00172 out_img->header = msg->header;
00173 out_img->header.frame_id = transform.child_frame_id_;
00174 img_pub_.publish(out_img);
00175 }
00176 catch (cv::Exception &e)
00177 {
00178 ROS_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00179 }
00180
00181 prev_stamp_ = msg->header.stamp;
00182 }
00183
00184 void subscribe()
00185 {
00186 ROS_DEBUG("Subscribing to image topic.");
00187 if (config_.use_camera_info && config_.input_frame_id.empty())
00188 cam_sub_ = it_.subscribeCamera("image", 3, &ImageRotater::imageCallbackWithInfo, this);
00189 else
00190 img_sub_ = it_.subscribe("image", 3, &ImageRotater::imageCallback, this);
00191 }
00192
00193 void unsubscribe()
00194 {
00195 ROS_DEBUG("Unsubscribing from image topic.");
00196 img_sub_.shutdown();
00197 cam_sub_.shutdown();
00198 }
00199
00200 void connectCb(const image_transport::SingleSubscriberPublisher& ssp)
00201 {
00202 if (subscriber_count_++ == 0) {
00203 subscribe();
00204 }
00205 }
00206
00207 void disconnectCb(const image_transport::SingleSubscriberPublisher&)
00208 {
00209 subscriber_count_--;
00210 if (subscriber_count_ == 0) {
00211 unsubscribe();
00212 }
00213 }
00214
00215 public:
00216 ImageRotater(ros::NodeHandle nh = ros::NodeHandle()) : it_(nh), nh_(nh), subscriber_count_(0), angle_(0), prev_stamp_(0, 0)
00217 {
00218 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ImageRotater::connectCb, this, _1);
00219 image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&ImageRotater::disconnectCb, this, _1);
00220 img_pub_ = image_transport::ImageTransport(ros::NodeHandle(nh_, "rotated")).advertise("image", 1, connect_cb, disconnect_cb);
00221
00222 dynamic_reconfigure::Server<image_rotate::ImageRotateConfig>::CallbackType f =
00223 boost::bind(&ImageRotater::reconfigureCallback, this, _1, _2);
00224 srv.setCallback(f);
00225 }
00226 };
00227
00228 int main(int argc, char **argv)
00229 {
00230 ros::init(argc, argv, "image_rotate", ros::init_options::AnonymousName);
00231
00232 ImageRotater ir;
00233 ros::spin();
00234 }