Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <QFrame>
00031 #include <QImage>
00032 #include <QPainter>
00033 #include <QPaintEvent>
00034 #include <QTimer>
00035 #include <QVector>
00036
00037
00038 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
00039 # include <ros/ros.h>
00040
00041 # include <std_srvs/Empty.h>
00042 # include <turtlesim/Spawn.h>
00043 # include <turtlesim/Kill.h>
00044 # include <map>
00045
00046 # include "turtle.h"
00047 #endif
00048
00049 namespace turtlesim
00050 {
00051
00052 class TurtleFrame : public QFrame
00053 {
00054 Q_OBJECT
00055 public:
00056 TurtleFrame(QWidget* parent = 0, Qt::WindowFlags f = 0);
00057 ~TurtleFrame();
00058
00059 std::string spawnTurtle(const std::string& name, float x, float y, float angle);
00060 std::string spawnTurtle(const std::string& name, float x, float y, float angle, size_t index);
00061
00062 protected:
00063 void paintEvent(QPaintEvent* event);
00064
00065 private slots:
00066 void onUpdate();
00067
00068 private:
00069 void updateTurtles();
00070 void clear();
00071 bool hasTurtle(const std::string& name);
00072
00073 bool clearCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00074 bool resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00075 bool spawnCallback(turtlesim::Spawn::Request&, turtlesim::Spawn::Response&);
00076 bool killCallback(turtlesim::Kill::Request&, turtlesim::Kill::Response&);
00077
00078 ros::NodeHandle nh_;
00079 QTimer* update_timer_;
00080 QImage path_image_;
00081 QPainter path_painter_;
00082
00083 uint64_t frame_count_;
00084
00085 ros::WallTime last_turtle_update_;
00086
00087 ros::ServiceServer clear_srv_;
00088 ros::ServiceServer reset_srv_;
00089 ros::ServiceServer spawn_srv_;
00090 ros::ServiceServer kill_srv_;
00091
00092 typedef std::map<std::string, TurtlePtr> M_Turtle;
00093 M_Turtle turtles_;
00094 uint32_t id_counter_;
00095
00096 QVector<QImage> turtle_images_;
00097
00098 float meter_;
00099 float width_in_meters_;
00100 float height_in_meters_;
00101 };
00102
00103 }