3636#include < boost/foreach.hpp>
3737
3838#include < OgreTextureManager.h>
39+ #include < opencv2/imgproc/imgproc.hpp>
3940
41+ #include < cv_bridge/cv_bridge.h>
42+ #include < geometry_msgs/Vector3Stamped.h>
4043#include < sensor_msgs/image_encodings.h>
44+ #include < tf2_ros/transform_listener.h>
45+ #include < tf2_ros/transform_broadcaster.h>
46+ #include < tf2_geometry_msgs/tf2_geometry_msgs.h>
4147
4248#include " rviz/image/ros_image_texture.h"
4349
@@ -49,9 +55,12 @@ ROSImageTexture::ROSImageTexture()
4955, width_(0 )
5056, height_(0 )
5157, median_frames_(5 )
58+ , target_frame_(" " )
5259{
5360 empty_image_.load (" no_image.png" , Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
5461
62+ tf_sub_.reset (new tf2_ros::TransformListener (tf_buffer_));
63+
5564 static uint32_t count = 0 ;
5665 std::stringstream ss;
5766 ss << " ROSImageTexture" << count++;
@@ -88,6 +97,11 @@ void ROSImageTexture::setMedianFrames( unsigned median_frames )
8897 median_frames_ = median_frames;
8998}
9099
100+ void ROSImageTexture::setRotateImageFrame (std::string target_frame)
101+ {
102+ target_frame_ = target_frame;
103+ }
104+
91105double ROSImageTexture::updateMedian ( std::deque<double >& buffer, double value )
92106{
93107 // update buffer
@@ -165,29 +179,108 @@ void ROSImageTexture::normalize( T* image_data, size_t image_data_size, std::vec
165179 }
166180}
167181
182+ sensor_msgs::Image::Ptr ROSImageTexture::rotateImage (sensor_msgs::Image::ConstPtr msg)
183+ {
184+ // Convert the image into something opencv can handle.
185+ cv::Mat in_image = cv_bridge::toCvShare (msg, msg->encoding )->image ;
186+
187+ // Compute the output image size.
188+ int max_dim = in_image.cols > in_image.rows ? in_image.cols : in_image.rows ;
189+ int min_dim = in_image.cols < in_image.rows ? in_image.cols : in_image.rows ;
190+ int noblack_dim = min_dim / sqrt (2 );
191+ int diag_dim = sqrt (in_image.cols *in_image.cols + in_image.rows *in_image.rows );
192+ int candidates[] = {noblack_dim, min_dim, max_dim, diag_dim, diag_dim}; // diag_dim repeated to simplify limit case.
193+ int output_image_size = 2 ;
194+ int step = output_image_size;
195+ int out_size = candidates[step] + (candidates[step + 1 ] - candidates[step]) * (output_image_size - step);
196+
197+ geometry_msgs::Vector3Stamped target_vector;
198+ target_vector.header .stamp = msg->header .stamp ;
199+ target_vector.header .frame_id = target_frame_;
200+ target_vector.vector .z = 1 ;
201+ if (!target_frame_.empty ())
202+ {
203+ // Transform the target vector into the image frame.
204+ try
205+ {
206+ geometry_msgs::TransformStamped transform = tf_buffer_.lookupTransform (
207+ target_frame_, msg->header .frame_id , msg->header .stamp );
208+ tf2::doTransform (target_vector, target_vector, transform);
209+ }
210+ catch (tf2::LookupException& e)
211+ {
212+ ROS_ERROR_THROTTLE (30 , " Error rotating image: %s" , e.what ());
213+ }
214+ }
215+
216+ // Transform the source vector into the image frame.
217+ geometry_msgs::Vector3Stamped source_vector;
218+ source_vector.header .stamp = msg->header .stamp ;
219+ source_vector.header .frame_id = msg->header .frame_id ;
220+ source_vector.vector .y = -1 ;
221+ if (!msg->header .frame_id .empty ())
222+ {
223+ try
224+ {
225+ geometry_msgs::TransformStamped transform = tf_buffer_.lookupTransform (
226+ msg->header .frame_id , msg->header .frame_id , msg->header .stamp );
227+ tf2::doTransform (source_vector, source_vector, transform);
228+ }
229+ catch (tf2::LookupException& e)
230+ {
231+ ROS_ERROR_THROTTLE (30 , " Error rotating image: %s" , e.what ());
232+ }
233+ }
234+
235+ // Calculate the angle of the rotation.
236+ double angle = 0 ;
237+ if ((target_vector.vector .x != 0 || target_vector.vector .y != 0 ) &&
238+ (source_vector.vector .x != 0 || source_vector.vector .y != 0 ))
239+ {
240+ angle = atan2 (target_vector.vector .y , target_vector.vector .x );
241+ angle -= atan2 (source_vector.vector .y , source_vector.vector .x );
242+ }
243+
244+ // Compute the rotation matrix.
245+ cv::Mat rot_matrix = cv::getRotationMatrix2D (cv::Point2f (in_image.cols / 2.0 , in_image.rows / 2.0 ), 180 * angle / M_PI, 1 );
246+ cv::Mat translation = rot_matrix.col (2 );
247+ rot_matrix.at <double >(0 , 2 ) += (out_size - in_image.cols ) / 2.0 ;
248+ rot_matrix.at <double >(1 , 2 ) += (out_size - in_image.rows ) / 2.0 ;
249+
250+ // Do the rotation
251+ cv::Mat out_image;
252+ cv::warpAffine (in_image, out_image, rot_matrix, cv::Size (out_size, out_size));
253+
254+ sensor_msgs::Image::Ptr dst_msg = cv_bridge::CvImage (msg->header , msg->encoding , out_image).toImageMsg ();
255+ dst_msg->header .frame_id = target_frame_;
256+ return dst_msg;
257+ }
258+
168259bool ROSImageTexture::update ()
169260{
170- sensor_msgs::Image::ConstPtr image ;
261+ sensor_msgs::Image::ConstPtr raw_image ;
171262 bool new_image = false ;
172263 {
173264 boost::mutex::scoped_lock lock (mutex_);
174265
175- image = current_image_;
266+ raw_image = current_image_;
176267 new_image = new_image_;
177268 }
178269
179- if (!image || !new_image)
270+ if (!raw_image || !new_image)
180271 {
181272 return false ;
182273 }
183274
184275 new_image_ = false ;
185276
186- if (image ->data .empty ())
277+ if (raw_image ->data .empty ())
187278 {
188279 return false ;
189280 }
190281
282+ sensor_msgs::Image::Ptr image = rotateImage (raw_image);
283+
191284 Ogre::PixelFormat format = Ogre::PF_R8G8B8;
192285 Ogre::Image ogre_image;
193286 std::vector<uint8_t > buffer;
0 commit comments