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 <wx/wx.h>
00044
00045 #define PI 3.14159265
00046
00047 namespace turtlesim
00048 {
00049
00050 struct Vector2
00051 {
00052 Vector2()
00053 : x(0.0)
00054 , y(0.0)
00055 {}
00056
00057 Vector2(float _x, float _y)
00058 : x(_x)
00059 , y(_y)
00060 {}
00061
00062 bool operator==(const Vector2& rhs)
00063 {
00064 return x == rhs.x && y == rhs.y;
00065 }
00066
00067 bool operator!=(const Vector2& rhs)
00068 {
00069 return x != rhs.x || y != rhs.y;
00070 }
00071
00072 float x;
00073 float y;
00074 };
00075
00076 class Turtle
00077 {
00078 public:
00079 Turtle(const ros::NodeHandle& nh, const wxImage& turtle_image, const Vector2& pos, float orient);
00080
00081 void update(double dt, wxMemoryDC& path_dc, const wxImage& path_image, wxColour background_color, float canvas_width, float canvas_height);
00082 void paint(wxDC& dc);
00083 private:
00084 void velocityCallback(const VelocityConstPtr& vel);
00085 bool setPenCallback(turtlesim::SetPen::Request&, turtlesim::SetPen::Response&);
00086 bool teleportRelativeCallback(turtlesim::TeleportRelative::Request&, turtlesim::TeleportRelative::Response&);
00087 bool teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request&, turtlesim::TeleportAbsolute::Response&);
00088
00089 ros::NodeHandle nh_;
00090
00091 wxImage turtle_image_;
00092 wxBitmap turtle_;
00093
00094 Vector2 pos_;
00095 float orient_;
00096
00097 float lin_vel_;
00098 float ang_vel_;
00099 bool pen_on_;
00100 wxPen pen_;
00101
00102 ros::Subscriber velocity_sub_;
00103 ros::Publisher pose_pub_;
00104 ros::Publisher color_pub_;
00105 ros::ServiceServer set_pen_srv_;
00106 ros::ServiceServer teleport_relative_srv_;
00107 ros::ServiceServer teleport_absolute_srv_;
00108
00109 ros::WallTime last_command_time_;
00110
00111 float meter_;
00112
00113 struct TeleportRequest
00114 {
00115 TeleportRequest(float x, float y, float _theta, float _linear, bool _relative)
00116 : pos(x, y)
00117 , theta(_theta)
00118 , linear(_linear)
00119 , relative(_relative)
00120 {}
00121
00122 Vector2 pos;
00123 float theta;
00124 float linear;
00125 bool relative;
00126 };
00127 typedef std::vector<TeleportRequest> V_TeleportRequest;
00128 V_TeleportRequest teleport_requests_;
00129 };
00130 typedef boost::shared_ptr<Turtle> TurtlePtr;
00131
00132 }
00133
00134 #endif