46 #include <jsk_topic_tools/log_utils.h>
52 #include <jsk_pcl_ros/ImageRotateConfig.h>
53 #include <geometry_msgs/Vector3Stamped.h>
56 #include <opencv2/imgproc/imgproc.hpp>
57 #include <dynamic_reconfigure/server.h>
60 #if ROS_VERSION_MINIMUM(1, 10, 0)
75 dynamic_reconfigure::Server<jsk_pcl_ros::ImageRotateConfig>
srv;
122 const std::string &
frameWithDefault(
const std::string &frame,
const std::string &image_frame)
140 const std::string& source_frame_id,
const ros::Time& time,
141 const std::string& fixed_frame_id,
147 geometry_msgs::TransformStamped trans
148 =
tf2_client_->lookupTransform(input_frame_id, source_frame_id,
151 Eigen::Affine3d transform_eigen;
155 tf::Vector3
origin = tf::Vector3(0, 0, 0);
156 tf::Vector3
end = input_vector;
157 tf::Vector3 output = (transform_tf *
end) - (transform_tf *
origin);
160 target_vector.
frame_id_ = input_frame_id;
164 tf_sub_->waitForTransform(input_frame_id, target_time,
165 source_frame_id, time,
167 tf_sub_->transformVector(input_frame_id, target_time, input_vector,
168 fixed_frame_id, target_vector);
173 void do_work(
const sensor_msgs::ImageConstPtr&
msg,
const std::string input_frame_from_msg)
204 if ((target_vector_transformed.x() != 0 || target_vector_transformed.y() != 0) &&
205 (source_vector_transformed.x() != 0 || source_vector_transformed.y() != 0))
207 angle =
atan2(target_vector_transformed.y(), target_vector_transformed.x());
208 angle -=
atan2(source_vector_transformed.y(), source_vector_transformed.x());
212 if (
config_.max_angular_rate == 0)
219 else if (delta < -
M_PI)
223 if (delta > max_delta)
225 else if (delta < -max_delta)
234 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
246 transform.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
260 int max_dim = in_image.cols > in_image.rows ? in_image.cols : in_image.rows;
261 int min_dim = in_image.cols < in_image.rows ? in_image.cols : in_image.rows;
262 int noblack_dim = min_dim /
sqrt(2);
263 int diag_dim =
sqrt(in_image.cols*in_image.cols + in_image.rows*in_image.rows);
265 int candidates[] = { noblack_dim, min_dim, max_dim, diag_dim, diag_dim };
271 cv::Mat rot_matrix = cv::getRotationMatrix2D(cv::Point2f(in_image.cols / 2.0, in_image.rows / 2.0), 180 *
angle_ /
M_PI, 1);
272 cv::Mat translation = rot_matrix.col(2);
273 rot_matrix.at<
double>(0, 2) += (out_size - in_image.cols) / 2.0;
274 rot_matrix.at<
double>(1, 2) += (out_size - in_image.rows) / 2.0;
278 cv::warpAffine(in_image, out_image, rot_matrix, cv::Size(out_size, out_size));
282 out_img->header.frame_id =
transform.child_frame_id_;
285 catch (cv::Exception &e)
287 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
338 dynamic_reconfigure::Server<jsk_pcl_ros::ImageRotateConfig>::CallbackType
f =