diff --git a/include/turtlesim/turtle_frame.h b/include/turtlesim/turtle_frame.h
index 0ddd09413ef692eec96a4c321895c1fc8f6c377a..34b8f9f2910543096d3ecaf7d09add7bf76d1073 100644
--- a/include/turtlesim/turtle_frame.h
+++ b/include/turtlesim/turtle_frame.h
@@ -33,6 +33,7 @@
 #include <QPaintEvent>
 #include <QTimer>
 #include <QVector>
+#include <turtlesim_xl/img.h>
 
 // This prevents a MOC error with versions of boost >= 1.48
 #ifndef Q_MOC_RUN  // See: https://bugreports.qt-project.org/browse/QTBUG-22829
@@ -59,8 +60,7 @@ public:
   std::string spawnTurtle(const std::string& name, float x, float y, float angle);
   std::string spawnTurtle(const std::string& name, float x, float y, float angle, size_t index);
 
-  void setShape(std::string shape);
-  void drawShape();
+  void drawImage(turtlesim_xl::img img);
 
 protected:
   void paintEvent(QPaintEvent* event);
@@ -102,8 +102,6 @@ private:
   float meter_;
   float width_in_meters_;
   float height_in_meters_;
-
-  std::string shape;
 };
 
 }
diff --git a/msg/img.msg b/msg/img.msg
index 02795b4e27ee45676630dc3e25b1395ac0bb5ca6..f31755ac0fa1b98b3c391e9ded636772bfeece78 100644
--- a/msg/img.msg
+++ b/msg/img.msg
@@ -1,4 +1,4 @@
 int64 x
 int64 y
-# uint64[] img
-string imgPath
\ No newline at end of file
+uint8[] img
+# string imgPath
\ No newline at end of file
diff --git a/src/turtle_frame.cpp b/src/turtle_frame.cpp
index 5b89364a12ca57326313cf8c575c18f2be2240cf..dd272af315a3041a81a3858dd8ea9354146f0aad 100644
--- a/src/turtle_frame.cpp
+++ b/src/turtle_frame.cpp
@@ -28,6 +28,7 @@
  */
 
 #include "turtlesim/turtle_frame.h"
+#include <turtlesim_xl/img.h>
 
 #include <QPointF>
 
@@ -294,28 +295,50 @@ bool TurtleFrame::resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Resp
   return true;
 }
 
-void TurtleFrame::drawShape() {
-  path_painter_.setPen(QColor(0xff,0xff,0xff));
-  int xTurtleStart = 12*meter_;
-  int yTurtleStart = FRAME_HEIGHT - 7*meter_;
-  if(shape == "triangle") {
-    int xTopRight = xTurtleStart;
-    int xTopLeft = xTopRight/2;
-    int xBottom = (xTopLeft + xTopRight) / 2;
-
-    int yTop = yTurtleStart;
-    int yBottom = yTop + 5*meter_;
-
-    path_painter_.drawLine(xTopLeft, yTop, xTopRight, yTop);
-    path_painter_.drawLine(xTopLeft, yTop, xBottom, yBottom);
-    path_painter_.drawLine(xBottom, yBottom, xTopRight, yTop);
-  }else {
-    path_painter_.drawRect((12-5)*meter_,FRAME_HEIGHT-(7-5)*meter_,5*meter_,-5*meter_);
+void TurtleFrame::drawImage(turtlesim_xl::img imgData) {
+  QPointF point;
+  
+  point.setX(130);
+  point.setY(140);
+
+  // const uint8_t *rawImg = imgData.img.data();
+  std::vector<uint8_t> rawImg;
+  for(uint8_t nr : imgData.img) {
+    rawImg.push_back(nr);
   }
-}
 
-void TurtleFrame::setShape(std::string shape) {
-  this->shape = shape;
+  const char *c = reinterpret_cast<const char *>(rawImg.data());
+
+  QByteArray byAr = QByteArray(c);
+  // for(uint8_t nr : imgData.img) {
+  //   // byAr.append(nr);
+  //   // char byte = nr;
+  //   // byAr.append(byte);
+
+  //   // QByteArray tmp = QByteArray::fromRawData(&byte, sizeof(nr));
+  //   // byAr += tmp;
+
+  //   const char *c = reinterpret_cast<const char *>(&nr);
+  //   byAr.append(c);
+
+  //   if(i % 250 == 0 && nr != 0) {
+  //     ROS_INFO("img data: %d; char: %d; QByte: %d", nr, c, byAr.at(i));
+  //   }
+  // }
+  ROS_INFO("Img Count: %d; QByte Count: %d", imgData.img.size() , byAr.size());
+
+  QImage img;
+  img.loadFromData(byAr);
+  
+  ROS_INFO("Draw msg img at: x = %d; y = %d", 130, 140);
+  path_painter_.drawImage(point, img);
+
+  // ROS_INFO("Draw loaded img at: x = %d; y = %d", 230, 240);
+  // point.setX(230);
+  // point.setY(240);
+  // img.load("/home/tsu/catkin_ws/src/turtleswarm/images/test.png");
+
+  // path_painter_.drawImage(point, img);
 }
 
 }
diff --git a/src/turtlesim_xl.cpp b/src/turtlesim_xl.cpp
index 584f20df5e2dafdf69ec3f7355ac5a97197097c3..57ecea8f193decbd5cdccb0b1631616212c2db7a 100644
--- a/src/turtlesim_xl.cpp
+++ b/src/turtlesim_xl.cpp
@@ -36,7 +36,6 @@
 
 class TurtleApp : public QApplication
 {
-  turtlesim_xl::img shapeData;
   ros::Subscriber shapeSub;
   turtlesim::TurtleFrame* frame;
 public:
@@ -57,9 +56,6 @@ public:
 
   int exec(std::string shape = "rectangle")
   {
-    frame->setShape(shape);
-    ROS_INFO("Offset before calling draw: x = %d; y = %d", shapeData.x, shapeData.y);
-    frame->drawShape();
     frame->show();
 
     return QApplication::exec();
@@ -67,10 +63,8 @@ public:
 
 private:
   void updateShape(turtlesim_xl::img data) {
-      shapeData = data;
       ROS_INFO("NEW SHAPE DATA SAVED");
-      frame->setShape("triangle");
-      frame->drawShape();
+      frame->drawImage(data);
   }
 };