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