turtle_frame.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "turtlesim/turtle_frame.h"
00031 
00032 #include <QPointF>
00033 
00034 #include <ros/package.h>
00035 #include <cstdlib>
00036 #include <ctime>
00037 
00038 #define DEFAULT_BG_R 0x45
00039 #define DEFAULT_BG_G 0x56
00040 #define DEFAULT_BG_B 0xff
00041 
00042 namespace turtlesim
00043 {
00044 
00045 TurtleFrame::TurtleFrame(QWidget* parent, Qt::WindowFlags f)
00046 : QFrame(parent, f)
00047 , path_image_(500, 500, QImage::Format_ARGB32)
00048 , path_painter_(&path_image_)
00049 , frame_count_(0)
00050 , id_counter_(0)
00051 {
00052   setFixedSize(500, 500);
00053   setWindowTitle("TurtleSim");
00054 
00055   srand(time(NULL));
00056 
00057   update_timer_ = new QTimer(this);
00058   update_timer_->setInterval(16);
00059   update_timer_->start();
00060 
00061   connect(update_timer_, SIGNAL(timeout()), this, SLOT(onUpdate()));
00062 
00063   nh_.setParam("background_r", DEFAULT_BG_R);
00064   nh_.setParam("background_g", DEFAULT_BG_G);
00065   nh_.setParam("background_b", DEFAULT_BG_B);
00066 
00067   QVector<QString> turtles;
00068   turtles.append("box-turtle.png");
00069   turtles.append("robot-turtle.png");
00070   turtles.append("sea-turtle.png");
00071   turtles.append("diamondback.png");
00072   turtles.append("electric.png");
00073   turtles.append("fuerte.png");
00074   turtles.append("groovy.png");
00075   turtles.append("hydro.svg");
00076   turtles.append("indigo.svg");
00077   turtles.append("jade.png");
00078 
00079   QString images_path = (ros::package::getPath("turtlesim") + "/images/").c_str();
00080   for (int i = 0; i < turtles.size(); ++i)
00081   {
00082     QImage img;
00083     img.load(images_path + turtles[i]);
00084     turtle_images_.append(img);
00085   }
00086 
00087   meter_ = turtle_images_[0].height();
00088 
00089   clear();
00090 
00091   clear_srv_ = nh_.advertiseService("clear", &TurtleFrame::clearCallback, this);
00092   reset_srv_ = nh_.advertiseService("reset", &TurtleFrame::resetCallback, this);
00093   spawn_srv_ = nh_.advertiseService("spawn", &TurtleFrame::spawnCallback, this);
00094   kill_srv_ = nh_.advertiseService("kill", &TurtleFrame::killCallback, this);
00095 
00096   ROS_INFO("Starting turtlesim with node name %s", ros::this_node::getName().c_str()) ;
00097 
00098   width_in_meters_ = (width() - 1) / meter_;
00099   height_in_meters_ = (height() - 1) / meter_;
00100   spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
00101 
00102   // spawn all available turtle types
00103   if(FALSE)
00104   {
00105     for(int index = 0; index < turtles.size(); ++index)
00106     {
00107       QString name = turtles[index];
00108       name = name.split(".").first();
00109       name.replace(QString("-"), QString(""));
00110       spawnTurtle(name.toStdString(), 1.0 + 1.5 * (index % 7), 1.0 + 1.5 * (index / 7), PI / 2.0, index);
00111     }
00112   }
00113 }
00114 
00115 TurtleFrame::~TurtleFrame()
00116 {
00117   delete update_timer_;
00118 }
00119 
00120 bool TurtleFrame::spawnCallback(turtlesim::Spawn::Request& req, turtlesim::Spawn::Response& res)
00121 {
00122   std::string name = spawnTurtle(req.name, req.x, req.y, req.theta);
00123   if (name.empty())
00124   {
00125     ROS_ERROR("A turtled named [%s] already exists", req.name.c_str());
00126     return false;
00127   }
00128 
00129   res.name = name;
00130 
00131   return true;
00132 }
00133 
00134 bool TurtleFrame::killCallback(turtlesim::Kill::Request& req, turtlesim::Kill::Response&)
00135 {
00136   M_Turtle::iterator it = turtles_.find(req.name);
00137   if (it == turtles_.end())
00138   {
00139     ROS_ERROR("Tried to kill turtle [%s], which does not exist", req.name.c_str());
00140     return false;
00141   }
00142 
00143   turtles_.erase(it);
00144   update();
00145 
00146   return true;
00147 }
00148 
00149 bool TurtleFrame::hasTurtle(const std::string& name)
00150 {
00151   return turtles_.find(name) != turtles_.end();
00152 }
00153 
00154 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle)
00155 {
00156   return spawnTurtle(name, x, y, angle, rand() % turtle_images_.size());
00157 }
00158 
00159 std::string TurtleFrame::spawnTurtle(const std::string& name, float x, float y, float angle, size_t index)
00160 {
00161   std::string real_name = name;
00162   if (real_name.empty())
00163   {
00164     do
00165     {
00166       std::stringstream ss;
00167       ss << "turtle" << ++id_counter_;
00168       real_name = ss.str();
00169     } while (hasTurtle(real_name));
00170   }
00171   else
00172   {
00173     if (hasTurtle(real_name))
00174     {
00175       return "";
00176     }
00177   }
00178 
00179   TurtlePtr t(new Turtle(ros::NodeHandle(real_name), turtle_images_[index], QPointF(x, height_in_meters_ - y), angle));
00180   turtles_[real_name] = t;
00181   update();
00182 
00183   ROS_INFO("Spawning turtle [%s] at x=[%f], y=[%f], theta=[%f]", real_name.c_str(), x, y, angle);
00184 
00185   return real_name;
00186 }
00187 
00188 void TurtleFrame::clear()
00189 {
00190   int r = DEFAULT_BG_R;
00191   int g = DEFAULT_BG_G;
00192   int b = DEFAULT_BG_B;
00193 
00194   nh_.param("background_r", r, r);
00195   nh_.param("background_g", g, g);
00196   nh_.param("background_b", b, b);
00197 
00198   path_image_.fill(qRgb(r, g, b));
00199   update();
00200 }
00201 
00202 void TurtleFrame::onUpdate()
00203 {
00204   ros::spinOnce();
00205 
00206   updateTurtles();
00207 
00208   if (!ros::ok())
00209   {
00210     close();
00211   }
00212 }
00213 
00214 void TurtleFrame::paintEvent(QPaintEvent*)
00215 {
00216   QPainter painter(this);
00217 
00218   painter.drawImage(QPoint(0, 0), path_image_);
00219 
00220   M_Turtle::iterator it = turtles_.begin();
00221   M_Turtle::iterator end = turtles_.end();
00222   for (; it != end; ++it)
00223   {
00224     it->second->paint(painter);
00225   }
00226 }
00227 
00228 void TurtleFrame::updateTurtles()
00229 {
00230   if (last_turtle_update_.isZero())
00231   {
00232     last_turtle_update_ = ros::WallTime::now();
00233     return;
00234   }
00235 
00236   bool modified = false;
00237   M_Turtle::iterator it = turtles_.begin();
00238   M_Turtle::iterator end = turtles_.end();
00239   for (; it != end; ++it)
00240   {
00241     modified |= it->second->update(0.001 * update_timer_->interval(), path_painter_, path_image_, width_in_meters_, height_in_meters_);
00242   }
00243   if (modified)
00244   {
00245     update();
00246   }
00247 
00248   ++frame_count_;
00249 }
00250 
00251 
00252 bool TurtleFrame::clearCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00253 {
00254   ROS_INFO("Clearing turtlesim.");
00255   clear();
00256   return true;
00257 }
00258 
00259 bool TurtleFrame::resetCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
00260 {
00261   ROS_INFO("Resetting turtlesim.");
00262   turtles_.clear();
00263   id_counter_ = 0;
00264   spawnTurtle("", width_in_meters_ / 2.0, height_in_meters_ / 2.0, 0);
00265   clear();
00266   return true;
00267 }
00268 
00269 }


turtlesim
Author(s): Josh Faust
autogenerated on Sun Mar 20 2016 04:51:25