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 #ifndef TURTLESIM_TURTLE_H
00031 #define TURTLESIM_TURTLE_H
00032
00033
00034 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829
00035 # include <ros/ros.h>
00036 # include <boost/shared_ptr.hpp>
00037
00038 # include <turtlesim/Pose.h>
00039 # include <geometry_msgs/Twist.h>
00040 # include <turtlesim/SetPen.h>
00041 # include <turtlesim/TeleportRelative.h>
00042 # include <turtlesim/TeleportAbsolute.h>
00043 # include <turtlesim/Color.h>
00044 #endif
00045
00046 #include <QImage>
00047 #include <QPainter>
00048 #include <QPen>
00049 #include <QPointF>
00050
00051 #define PI 3.14159265
00052
00053 namespace turtlesim
00054 {
00055
00056 class Turtle
00057 {
00058 public:
00059 Turtle(const ros::NodeHandle& nh, const QImage& turtle_image, const QPointF& pos, float orient);
00060
00061 bool update(double dt, QPainter& path_painter, const QImage& path_image, qreal canvas_width, qreal canvas_height);
00062 void paint(QPainter &painter);
00063 private:
00064 void velocityCallback(const geometry_msgs::Twist::ConstPtr& vel);
00065 bool setPenCallback(turtlesim::SetPen::Request&, turtlesim::SetPen::Response&);
00066 bool teleportRelativeCallback(turtlesim::TeleportRelative::Request&, turtlesim::TeleportRelative::Response&);
00067 bool teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request&, turtlesim::TeleportAbsolute::Response&);
00068
00069 void rotateImage();
00070
00071 ros::NodeHandle nh_;
00072
00073 QImage turtle_image_;
00074 QImage turtle_rotated_image_;
00075
00076 QPointF pos_;
00077 qreal orient_;
00078
00079 qreal lin_vel_;
00080 qreal ang_vel_;
00081 bool pen_on_;
00082 QPen pen_;
00083
00084 ros::Subscriber velocity_sub_;
00085 ros::Publisher pose_pub_;
00086 ros::Publisher color_pub_;
00087 ros::ServiceServer set_pen_srv_;
00088 ros::ServiceServer teleport_relative_srv_;
00089 ros::ServiceServer teleport_absolute_srv_;
00090
00091 ros::WallTime last_command_time_;
00092
00093 float meter_;
00094
00095 struct TeleportRequest
00096 {
00097 TeleportRequest(float x, float y, qreal _theta, qreal _linear, bool _relative)
00098 : pos(x, y)
00099 , theta(_theta)
00100 , linear(_linear)
00101 , relative(_relative)
00102 {}
00103
00104 QPointF pos;
00105 qreal theta;
00106 qreal linear;
00107 bool relative;
00108 };
00109 typedef std::vector<TeleportRequest> V_TeleportRequest;
00110 V_TeleportRequest teleport_requests_;
00111 };
00112 typedef boost::shared_ptr<Turtle> TurtlePtr;
00113
00114 }
00115
00116 #endif