Skip to content
Snippets Groups Projects
Commit 5ff8e079 authored by Joel Vongehr's avatar Joel Vongehr
Browse files

added first version of parameter for drawing

parent cdb78617
No related branches found
No related tags found
No related merge requests found
......@@ -59,6 +59,9 @@ 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();
protected:
void paintEvent(QPaintEvent* event);
......@@ -99,6 +102,8 @@ private:
float meter_;
float width_in_meters_;
float height_in_meters_;
std::string shape;
};
}
......@@ -44,7 +44,10 @@
namespace turtlesim
{
TurtleFrame::TurtleFrame(QWidget* parent, Qt::WindowFlags f)
TurtleFrame::TurtleFrame(QWidget* parent, Qt::WindowFlags f):
TurtleFrame("rectangle", parent, f) {}
TurtleFrame::TurtleFrame(std::string shape, QWidget* parent, Qt::WindowFlags f)
: QFrame(parent, f)
, path_image_(FRAME_WIDTH, FRAME_HEIGHT, QImage::Format_ARGB32)
, path_painter_(&path_image_)
......@@ -105,8 +108,8 @@ TurtleFrame::TurtleFrame(QWidget* parent, Qt::WindowFlags f)
clear();
//temp draw shape (hardcoded) -----------------------------------
path_painter_.setPen(QColor(0xff,0xff,0xff)) ;
path_painter_.drawRect((12-5)*meter_,FRAME_HEIGHT-(7-5)*meter_,5*meter_,-5*meter_);
// path_painter_.setPen(QColor(0xff,0xff,0xff));
// path_painter_.drawRect((12-5)*meter_,FRAME_HEIGHT-(7-5)*meter_,5*meter_,-5*meter_);
//QPointF tmp01;
//tmp01.setX((12-5)*meter_);
//tmp01.setY(FRAME_HEIGHT-(7)*meter_);
......@@ -293,4 +296,28 @@ 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::setShape(std::string shape) {
this->shape = shape;
}
}
......@@ -45,9 +45,11 @@ public:
nh_.reset(new ros::NodeHandle);
}
int exec()
int exec(std::string shape = "rectangle")
{
turtlesim::TurtleFrame frame;
frame.setShape(shape);
frame.drawShape();
frame.show();
return QApplication::exec();
......@@ -56,7 +58,15 @@ public:
int main(int argc, char** argv)
{
/*
argv with launch file:
0: path to node
1: additional argument (the result of shape=... in this case)
2: name of the node
3: path to log
*/
TurtleApp app(argc, argv);
return app.exec();
std::string shape = argv[1];
return app.exec(shape);
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment