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  turtles.append("lunar.png");
80 
81  QString images_path = (ros::package::getPath("turtlesim") + "/images/").c_str();
82  for (int i = 0; i < turtles.size(); ++i)
83  {
84  QImage img;
85  img.load(images_path + turtles[i]);
86  turtle_images_.append(img);
87  }
88 
89  meter_ = turtle_images_[0].height();
90 
91  clear();
92 
97 
98  ROS_INFO("Starting turtlesim with node name %s", ros::this_node::getName().c_str()) ;
99 
100  width_in_meters_ = (width() - 1) / meter_;
101  height_in_meters_ = (height() - 1) / meter_;
102  spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
103 
104  // spawn all available turtle types
105  if(false)
106  {
107  for(int index = 0; index < turtles.size(); ++index)
108  {
109  QString name = turtles[index];
110  name = name.split(".").first();
111  name.replace(QString("-"), QString(""));
112  spawnTurtle(name.toStdString(), 1.0 + 1.5 * (index % 7), 1.0 + 1.5 * (index / 7), PI / 2.0, index);
113  }
114  }
115 }
116 
118 {
119  delete update_timer_;
120 }
121 
122 bool TurtleFrame::spawnCallback(turtlesim::Spawn::Request& req, turtlesim::Spawn::Response& res)
123 {
124  std::string name = spawnTurtle(req.name, req.x, req.y, req.theta);
125  if (name.empty())
126  {
127  ROS_ERROR("A turtled named [%s] already exists", req.name.c_str());
128  return false;
129  }
130 
131  res.name = name;
132 
133  return true;
134 }
135 
136 bool TurtleFrame::killCallback(turtlesim::Kill::Request& req, turtlesim::Kill::Response&)
137 {
138  M_Turtle::iterator it = turtles_.find(req.name);
139  if (it == turtles_.end())
140  {
141  ROS_ERROR("Tried to kill turtle [%s], which does not exist", req.name.c_str());
142  return false;
143  }
144 
145  turtles_.erase(it);
146  update();
147 
148  return true;
149 }
150 
151 bool TurtleFrame::hasTurtle(const std::string& name)
152 {
153  return turtles_.find(name) != turtles_.end();
154 }
155 
156 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle)
157 {
158  return spawnTurtle(name, x, y, angle, rand() % turtle_images_.size());
159 }
160 
161 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle, size_t index)
162 {
163  std::string real_name = name;
164  if (real_name.empty())
165  {
166  do
167  {
168  std::stringstream ss;
169  ss << "turtle" << ++id_counter_;
170  real_name = ss.str();
171  } while (hasTurtle(real_name));
172  }
173  else
174  {
175  if (hasTurtle(real_name))
176  {
177  return "";
178  }
179  }
180 
181  TurtlePtr t(new Turtle(ros::NodeHandle(real_name), turtle_images_[index], QPointF(x, height_in_meters_ - y), angle));
182  turtles_[real_name] = t;
183  update();
184 
185  ROS_INFO("Spawning turtle [%s] at x=[%f], y=[%f], theta=[%f]", real_name.c_str(), x, y, angle);
186 
187  return real_name;
188 }
189 
191 {
192  int r = DEFAULT_BG_R;
193  int g = DEFAULT_BG_G;
194  int b = DEFAULT_BG_B;
195 
196  nh_.param("background_r", r, r);
197  nh_.param("background_g", g, g);
198  nh_.param("background_b", b, b);
199 
200  path_image_.fill(qRgb(r, g, b));
201  update();
202 }
203 
205 {
206  ros::spinOnce();
207 
208  updateTurtles();
209 
210  if (!ros::ok())
211  {
212  close();
213  }
214 }
215 
216 void TurtleFrame::paintEvent(QPaintEvent*)
217 {
218  QPainter painter(this);
219 
220  painter.drawImage(QPoint(0, 0), path_image_);
221 
222  M_Turtle::iterator it = turtles_.begin();
223  M_Turtle::iterator end = turtles_.end();
224  for (; it != end; ++it)
225  {
226  it->second->paint(painter);
227  }
228 }
229 
231 {
233  {
235  return;
236  }
237 
238  bool modified = false;
239  M_Turtle::iterator it = turtles_.begin();
240  M_Turtle::iterator end = turtles_.end();
241  for (; it != end; ++it)
242  {
243  modified |= it->second->update(0.001 * update_timer_->interval(), path_painter_, path_image_, width_in_meters_, height_in_meters_);
244  }
245  if (modified)
246  {
247  update();
248  }
249 
250  ++frame_count_;
251 }
252 
253 
254 bool TurtleFrame::clearCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
255 {
256  ROS_INFO("Clearing turtlesim.");
257  clear();
258  return true;
259 }
260 
261 bool TurtleFrame::resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
262 {
263  ROS_INFO("Resetting turtlesim.");
264  turtles_.clear();
265  id_counter_ = 0;
266  spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
267  clear();
268  return true;
269 }
270 
271 }
#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
autogenerated on Fri Jun 7 2019 22:01:46