Skip to content

Commit 205475e

Browse files
committed
Rotate image with transformation from image frame to target one
1 parent 1da678a commit 205475e

File tree

7 files changed

+139
-6
lines changed

7 files changed

+139
-6
lines changed

CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,7 @@ endif()
106106
find_package(catkin REQUIRED
107107
COMPONENTS
108108
angles
109+
cv_bridge
109110
cmake_modules
110111
geometry_msgs
111112
image_geometry
@@ -127,6 +128,8 @@ find_package(catkin REQUIRED
127128
std_msgs
128129
std_srvs
129130
tf
131+
tf2
132+
tf2_geometry_msgs
130133
urdf
131134
visualization_msgs
132135
)

package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020

2121
<build_depend>assimp-dev</build_depend>
2222
<build_depend>cmake_modules</build_depend>
23+
<build_depend>cv_bridge</build_depend>
2324
<build_depend>eigen</build_depend>
2425
<build_depend>geometry_msgs</build_depend>
2526
<build_depend>image_geometry</build_depend>
@@ -51,6 +52,7 @@
5152
<build_depend>opengl</build_depend>
5253

5354
<run_depend>assimp</run_depend>
55+
<run_depend>cv_bridge</run_depend>
5456
<run_depend>eigen</run_depend>
5557
<run_depend>geometry_msgs</run_depend>
5658
<run_depend>image_geometry</run_depend>

src/rviz/CMakeLists.txt

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,15 @@ if(NEW_YAMLCPP_FOUND)
44
add_definitions(-DRVIZ_HAVE_YAMLCPP_05)
55
endif(NEW_YAMLCPP_FOUND)
66

7+
if(UNIX AND NOT APPLE)
8+
find_package(X11 REQUIRED)
9+
endif()
10+
11+
find_package(OpenCV REQUIRED core imgproc)
12+
713
add_subdirectory(default_plugin)
814

9-
include_directories(.)
15+
include_directories(. ${OpenCV_INCLUDE_DIRS})
1016

1117
# Build the version number and other build-time constants into the
1218
# source for access at run-time.
@@ -128,10 +134,12 @@ add_library( ${PROJECT_NAME}
128134
target_link_libraries(${PROJECT_NAME}
129135
${Boost_LIBRARIES}
130136
${catkin_LIBRARIES}
137+
${QT_LIBRARIES}
131138
${OGRE_OV_LIBRARIES_ABS}
132139
${OPENGL_LIBRARIES}
133-
${QT_LIBRARIES}
134140
${rviz_ADDITIONAL_LIBRARIES}
141+
${X11_X11_LIB}
142+
${OpenCV_LIBRARIES}
135143
assimp
136144
yaml-cpp
137145
)

src/rviz/default_plugin/image_display.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,8 @@ ImageDisplay::ImageDisplay()
7171
median_buffer_size_property_ = new IntProperty( "Median window", 5, "Window size for median filter used for computin min/max.",
7272
this, SLOT( updateNormalizeOptions() ) );
7373

74+
target_frame_property_ = new StringProperty( "Target Frame", "", "Target frame to rotate the image", this, SLOT( updateTargetFrame() ));
75+
7476
got_float_image_ = false;
7577
}
7678

@@ -154,6 +156,15 @@ void ImageDisplay::onDisable()
154156
clear();
155157
}
156158

159+
void ImageDisplay::updateTargetFrame()
160+
{
161+
std::string target_frame = target_frame_property_->getStdString();
162+
if (!target_frame.empty())
163+
{
164+
texture_.setRotateImageFrame(target_frame);
165+
}
166+
}
167+
157168
void ImageDisplay::updateNormalizeOptions()
158169
{
159170
if (got_float_image_)
@@ -242,6 +253,12 @@ void ImageDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
242253
got_float_image_ = got_float_image;
243254
updateNormalizeOptions();
244255
}
256+
257+
if (target_frame_property_->getStdString().empty())
258+
{
259+
target_frame_property_->setValue(QString(msg->header.frame_id.c_str()));
260+
}
261+
245262
texture_.addMessage(msg);
246263
}
247264

src/rviz/default_plugin/image_display.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,7 @@ Q_OBJECT
7474

7575
public Q_SLOTS:
7676
virtual void updateNormalizeOptions();
77+
virtual void updateTargetFrame();
7778

7879
protected:
7980
// overrides from Display
@@ -100,6 +101,7 @@ public Q_SLOTS:
100101
FloatProperty* min_property_;
101102
FloatProperty* max_property_;
102103
IntProperty* median_buffer_size_property_;
104+
StringProperty* target_frame_property_;
103105
bool got_float_image_;
104106
};
105107

src/rviz/image/ros_image_texture.cpp

Lines changed: 97 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,14 @@
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+
91105
double 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+
168259
bool 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;

src/rviz/image/ros_image_texture.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@
4040
#include <boost/thread/mutex.hpp>
4141

4242
#include <ros/ros.h>
43+
#include <tf2_ros/transform_listener.h>
44+
#include <tf2_ros/transform_broadcaster.h>
4345

4446
#include <stdexcept>
4547

@@ -73,14 +75,19 @@ class ROSImageTexture
7375
// automatic range normalization
7476
void setNormalizeFloatImage( bool normalize, double min=0.0, double max=1.0 );
7577
void setMedianFrames( unsigned median_frames );
78+
void setRotateImageFrame(std::string source_frame);
7679

7780
private:
7881

7982
double updateMedian( std::deque<double>& buffer, double new_value );
8083

84+
sensor_msgs::Image::Ptr rotateImage(sensor_msgs::Image::ConstPtr msg);
85+
8186
template<typename T>
8287
void normalize( T* image_data, size_t image_data_size, std::vector<uint8_t> &buffer );
8388

89+
tf2_ros::Buffer tf_buffer_;
90+
boost::shared_ptr<tf2_ros::TransformListener> tf_sub_;
8491
sensor_msgs::Image::ConstPtr current_image_;
8592
boost::mutex mutex_;
8693
bool new_image_;
@@ -98,6 +105,7 @@ class ROSImageTexture
98105
unsigned median_frames_;
99106
std::deque<double> min_buffer_;
100107
std::deque<double> max_buffer_;
108+
std::string target_frame_;
101109
};
102110

103111
}

0 commit comments

Comments
 (0)