48 #include <image_rotate/ImageRotateConfig.h>
49 #include <geometry_msgs/Vector3Stamped.h>
52 #include <opencv2/imgproc/imgproc.hpp>
53 #include <dynamic_reconfigure/server.h>
64 image_rotate::ImageRotateConfig
config_;
65 dynamic_reconfigure::Server<image_rotate::ImageRotateConfig>
srv;
98 const std::string &
frameWithDefault(
const std::string &frame,
const std::string &image_frame)
105 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
107 do_work(msg, cam_info->header.frame_id);
112 do_work(msg, msg->header.frame_id);
115 void do_work(
const sensor_msgs::ImageConstPtr& msg,
const std::string input_frame_from_msg)
126 geometry_msgs::Vector3Stamped target_vector_transformed;
133 geometry_msgs::Vector3Stamped source_vector_transformed;
144 if ((target_vector_transformed.vector.x != 0 || target_vector_transformed.vector.y != 0) &&
145 (source_vector_transformed.vector.x != 0 || source_vector_transformed.vector.y != 0))
147 angle = atan2(target_vector_transformed.vector.y, target_vector_transformed.vector.x);
148 angle -= atan2(source_vector_transformed.vector.y, source_vector_transformed.vector.x);
156 double delta = fmod(angle -
angle_, 2.0 * M_PI);
159 else if (delta < - M_PI)
162 double max_delta =
config_.max_angular_rate * (msg->header.stamp -
prev_stamp_).toSec();
163 if (delta > max_delta)
165 else if (delta < -max_delta)
180 geometry_msgs::TransformStamped transform;
181 transform.transform.translation.x = 0;
182 transform.transform.translation.y = 0;
183 transform.transform.translation.z = 0;
185 transform.header.frame_id = msg->header.frame_id;
187 transform.header.stamp = msg->header.stamp;
197 int max_dim = in_image.cols > in_image.rows ? in_image.cols : in_image.rows;
198 int min_dim = in_image.cols < in_image.rows ? in_image.cols : in_image.rows;
199 int noblack_dim = min_dim / sqrt(2);
200 int diag_dim = sqrt(in_image.cols*in_image.cols + in_image.rows*in_image.rows);
202 int candidates[] = { noblack_dim, min_dim, max_dim, diag_dim, diag_dim };
204 out_size = candidates[
step] + (candidates[
step + 1] - candidates[
step]) * (
config_.output_image_size - step);
208 cv::Mat rot_matrix = cv::getRotationMatrix2D(cv::Point2f(in_image.cols / 2.0, in_image.rows / 2.0), 180 *
angle_ / M_PI, 1);
209 cv::Mat translation = rot_matrix.col(2);
210 rot_matrix.at<
double>(0, 2) += (out_size - in_image.cols) / 2.0;
211 rot_matrix.at<
double>(1, 2) += (out_size - in_image.rows) / 2.0;
215 cv::warpAffine(in_image, out_image, rot_matrix, cv::Size(out_size, out_size));
219 out_img->header.frame_id = transform.child_frame_id;
222 catch (cv::Exception &e)
224 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
274 dynamic_reconfigure::Server<image_rotate::ImageRotateConfig>::CallbackType
f =