turtle_frame.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "turtlesim/turtle_frame.h"
31 
32 #include <QPointF>
33 
34 #include <ros/package.h>
35 #include <cstdlib>
36 #include <ctime>
37 
38 #define DEFAULT_BG_R 0x45
39 #define DEFAULT_BG_G 0x56
40 #define DEFAULT_BG_B 0xff
41 
42 namespace turtlesim
43 {
44 
45 TurtleFrame::TurtleFrame(QWidget* parent, Qt::WindowFlags f)
46 : QFrame(parent, f)
47 , path_image_(500, 500, QImage::Format_ARGB32)
48 , path_painter_(&path_image_)
49 , frame_count_(0)
50 , id_counter_(0)
51 {
52  setFixedSize(500, 500);
53  setWindowTitle("TurtleSim");
54 
55  srand(time(NULL));
56 
57  update_timer_ = new QTimer(this);
58  update_timer_->setInterval(16);
59  update_timer_->start();
60 
61  connect(update_timer_, SIGNAL(timeout()), this, SLOT(onUpdate()));
62 
63  nh_.setParam("background_r", DEFAULT_BG_R);
64  nh_.setParam("background_g", DEFAULT_BG_G);
65  nh_.setParam("background_b", DEFAULT_BG_B);
66 
67  QVector<QString> turtles;
68  turtles.append("box-turtle.png");
69  turtles.append("robot-turtle.png");
70  turtles.append("sea-turtle.png");
71  turtles.append("diamondback.png");
72  turtles.append("electric.png");
73  turtles.append("fuerte.png");
74  turtles.append("groovy.png");
75  turtles.append("hydro.svg");
76  turtles.append("indigo.svg");
77  turtles.append("jade.png");
78  turtles.append("kinetic.png");
79 
80  QString images_path = (ros::package::getPath("turtlesim") + "/images/").c_str();
81  for (int i = 0; i < turtles.size(); ++i)
82  {
83  QImage img;
84  img.load(images_path + turtles[i]);
85  turtle_images_.append(img);
86  }
87 
88  meter_ = turtle_images_[0].height();
89 
90  clear();
91 
96 
97  ROS_INFO("Starting turtlesim with node name %s", ros::this_node::getName().c_str()) ;
98 
99  width_in_meters_ = (width() - 1) / meter_;
100  height_in_meters_ = (height() - 1) / meter_;
101  spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
102 
103  // spawn all available turtle types
104  if(false)
105  {
106  for(int index = 0; index < turtles.size(); ++index)
107  {
108  QString name = turtles[index];
109  name = name.split(".").first();
110  name.replace(QString("-"), QString(""));
111  spawnTurtle(name.toStdString(), 1.0 + 1.5 * (index % 7), 1.0 + 1.5 * (index / 7), PI / 2.0, index);
112  }
113  }
114 }
115 
117 {
118  delete update_timer_;
119 }
120 
121 bool TurtleFrame::spawnCallback(turtlesim::Spawn::Request& req, turtlesim::Spawn::Response& res)
122 {
123  std::string name = spawnTurtle(req.name, req.x, req.y, req.theta);
124  if (name.empty())
125  {
126  ROS_ERROR("A turtled named [%s] already exists", req.name.c_str());
127  return false;
128  }
129 
130  res.name = name;
131 
132  return true;
133 }
134 
135 bool TurtleFrame::killCallback(turtlesim::Kill::Request& req, turtlesim::Kill::Response&)
136 {
137  M_Turtle::iterator it = turtles_.find(req.name);
138  if (it == turtles_.end())
139  {
140  ROS_ERROR("Tried to kill turtle [%s], which does not exist", req.name.c_str());
141  return false;
142  }
143 
144  turtles_.erase(it);
145  update();
146 
147  return true;
148 }
149 
150 bool TurtleFrame::hasTurtle(const std::string& name)
151 {
152  return turtles_.find(name) != turtles_.end();
153 }
154 
155 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle)
156 {
157  return spawnTurtle(name, x, y, angle, rand() % turtle_images_.size());
158 }
159 
160 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle, size_t index)
161 {
162  std::string real_name = name;
163  if (real_name.empty())
164  {
165  do
166  {
167  std::stringstream ss;
168  ss << "turtle" << ++id_counter_;
169  real_name = ss.str();
170  } while (hasTurtle(real_name));
171  }
172  else
173  {
174  if (hasTurtle(real_name))
175  {
176  return "";
177  }
178  }
179 
180  TurtlePtr t(new Turtle(ros::NodeHandle(real_name), turtle_images_[index], QPointF(x, height_in_meters_ - y), angle));
181  turtles_[real_name] = t;
182  update();
183 
184  ROS_INFO("Spawning turtle [%s] at x=[%f], y=[%f], theta=[%f]", real_name.c_str(), x, y, angle);
185 
186  return real_name;
187 }
188 
190 {
191  int r = DEFAULT_BG_R;
192  int g = DEFAULT_BG_G;
193  int b = DEFAULT_BG_B;
194 
195  nh_.param("background_r", r, r);
196  nh_.param("background_g", g, g);
197  nh_.param("background_b", b, b);
198 
199  path_image_.fill(qRgb(r, g, b));
200  update();
201 }
202 
204 {
205  ros::spinOnce();
206 
207  updateTurtles();
208 
209  if (!ros::ok())
210  {
211  close();
212  }
213 }
214 
215 void TurtleFrame::paintEvent(QPaintEvent*)
216 {
217  QPainter painter(this);
218 
219  painter.drawImage(QPoint(0, 0), path_image_);
220 
221  M_Turtle::iterator it = turtles_.begin();
222  M_Turtle::iterator end = turtles_.end();
223  for (; it != end; ++it)
224  {
225  it->second->paint(painter);
226  }
227 }
228 
230 {
232  {
234  return;
235  }
236 
237  bool modified = false;
238  M_Turtle::iterator it = turtles_.begin();
239  M_Turtle::iterator end = turtles_.end();
240  for (; it != end; ++it)
241  {
242  modified |= it->second->update(0.001 * update_timer_->interval(), path_painter_, path_image_, width_in_meters_, height_in_meters_);
243  }
244  if (modified)
245  {
246  update();
247  }
248 
249  ++frame_count_;
250 }
251 
252 
253 bool TurtleFrame::clearCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
254 {
255  ROS_INFO("Clearing turtlesim.");
256  clear();
257  return true;
258 }
259 
260 bool TurtleFrame::resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
261 {
262  ROS_INFO("Resetting turtlesim.");
263  turtles_.clear();
264  id_counter_ = 0;
265  spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
266  clear();
267  return true;
268 }
269 
270 }
#define DEFAULT_BG_R
bool hasTurtle(const std::string &name)
bool spawnCallback(turtlesim::Spawn::Request &, turtlesim::Spawn::Response &)
ros::ServiceServer kill_srv_
Definition: turtle_frame.h:90
bool clearCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void paintEvent(QPaintEvent *event)
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer clear_srv_
Definition: turtle_frame.h:87
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
ros::NodeHandle nh_
Definition: turtle_frame.h:78
#define PI
Definition: turtle.h:51
#define ROS_INFO(...)
TurtleFrame(QWidget *parent=0, Qt::WindowFlags f=0)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
ROSLIB_DECL std::string getPath(const std::string &package_name)
bool killCallback(turtlesim::Kill::Request &, turtlesim::Kill::Response &)
bool resetCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
static WallTime now()
#define DEFAULT_BG_G
ros::ServiceServer spawn_srv_
Definition: turtle_frame.h:89
ros::ServiceServer reset_srv_
Definition: turtle_frame.h:88
std::string spawnTurtle(const std::string &name, float x, float y, float angle)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::WallTime last_turtle_update_
Definition: turtle_frame.h:85
#define DEFAULT_BG_B
QVector< QImage > turtle_images_
Definition: turtle_frame.h:96


turtlesim
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sun Oct 18 2020 13:09:45