turtle.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.h"
31 
32 #include <QColor>
33 #include <QRgb>
34 
35 #define DEFAULT_PEN_R 0xb3
36 #define DEFAULT_PEN_G 0xb8
37 #define DEFAULT_PEN_B 0xff
38 
39 namespace turtlesim
40 {
41 
42 Turtle::Turtle(const ros::NodeHandle& nh, const QImage& turtle_image, const QPointF& pos, float orient)
43 : nh_(nh)
44 , turtle_image_(turtle_image)
45 , pos_(pos)
46 , orient_(orient)
47 , lin_vel_x_(0.0)
48 , lin_vel_y_(0.0)
49 , ang_vel_(0.0)
50 , pen_on_(true)
52 {
53  pen_.setWidth(3);
54 
55  velocity_sub_ = nh_.subscribe("cmd_vel", 1, &Turtle::velocityCallback, this);
56  pose_pub_ = nh_.advertise<Pose>("pose", 1);
57  color_pub_ = nh_.advertise<Color>("color_sensor", 1);
61 
62  meter_ = turtle_image_.height();
63  rotateImage();
64 }
65 
66 
67 void Turtle::velocityCallback(const geometry_msgs::Twist::ConstPtr& vel)
68 {
70  lin_vel_x_ = vel->linear.x;
71  lin_vel_y_ = vel->linear.y;
72  ang_vel_ = vel->angular.z;
73 }
74 
75 bool Turtle::setPenCallback(turtlesim::SetPen::Request& req, turtlesim::SetPen::Response&)
76 {
77  pen_on_ = !req.off;
78  if (req.off)
79  {
80  return true;
81  }
82 
83  QPen pen(QColor(req.r, req.g, req.b));
84  if (req.width != 0)
85  {
86  pen.setWidth(req.width);
87  }
88 
89  pen_ = pen;
90  return true;
91 }
92 
93 bool Turtle::teleportRelativeCallback(turtlesim::TeleportRelative::Request& req, turtlesim::TeleportRelative::Response&)
94 {
95  teleport_requests_.push_back(TeleportRequest(0, 0, req.angular, req.linear, true));
96  return true;
97 }
98 
99 bool Turtle::teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request& req, turtlesim::TeleportAbsolute::Response&)
100 {
101  teleport_requests_.push_back(TeleportRequest(req.x, req.y, req.theta, 0, false));
102  return true;
103 }
104 
106 {
107  QTransform transform;
108  transform.rotate(-orient_ * 180.0 / PI + 90.0);
109  turtle_rotated_image_ = turtle_image_.transformed(transform);
110 }
111 
112 bool Turtle::update(double dt, QPainter& path_painter, const QImage& path_image, qreal canvas_width, qreal canvas_height)
113 {
114  bool modified = false;
115  qreal old_orient = orient_;
116 
117  // first process any teleportation requests, in order
118  V_TeleportRequest::iterator it = teleport_requests_.begin();
119  V_TeleportRequest::iterator end = teleport_requests_.end();
120  for (; it != end; ++it)
121  {
122  const TeleportRequest& req = *it;
123 
124  QPointF old_pos = pos_;
125  if (req.relative)
126  {
127  orient_ += req.theta;
128  pos_.rx() += std::cos(orient_) * req.linear;
129  pos_.ry() += - std::sin(orient_) * req.linear;
130  }
131  else
132  {
133  pos_.setX(req.pos.x());
134  pos_.setY(std::max(0.0, static_cast<double>(canvas_height - req.pos.y())));
135  orient_ = req.theta;
136  }
137 
138  if (pen_on_)
139  {
140  path_painter.setPen(pen_);
141  path_painter.drawLine(pos_ * meter_, old_pos * meter_);
142  }
143  modified = true;
144  }
145 
146  teleport_requests_.clear();
147 
149  {
150  lin_vel_x_ = 0.0;
151  lin_vel_y_ = 0.0;
152  ang_vel_ = 0.0;
153  }
154 
155  QPointF old_pos = pos_;
156 
157  orient_ = orient_ + ang_vel_ * dt;
158  // Keep orient_ between -pi and +pi
159  orient_ -= 2*PI * std::floor((orient_ + PI)/(2*PI));
160  pos_.rx() += std::cos(orient_) * lin_vel_x_ * dt
161  - std::sin(orient_) * lin_vel_y_ * dt;
162  pos_.ry() -= std::cos(orient_) * lin_vel_y_ * dt
163  + std::sin(orient_) * lin_vel_x_ * dt;
164 
165  // Clamp to screen size
166  if (pos_.x() < 0 || pos_.x() > canvas_width ||
167  pos_.y() < 0 || pos_.y() > canvas_height)
168  {
169  ROS_WARN("Oh no! I hit the wall! (Clamping from [x=%f, y=%f])", pos_.x(), pos_.y());
170  }
171 
172  pos_.setX(std::min(std::max(static_cast<double>(pos_.x()), 0.0), static_cast<double>(canvas_width)));
173  pos_.setY(std::min(std::max(static_cast<double>(pos_.y()), 0.0), static_cast<double>(canvas_height)));
174 
175  // Publish pose of the turtle
176  Pose p;
177  p.x = pos_.x();
178  p.y = canvas_height - pos_.y();
179  p.theta = orient_;
180  p.linear_velocity = std::sqrt(lin_vel_x_ * lin_vel_x_ + lin_vel_y_ * lin_vel_y_);
181  p.angular_velocity = ang_vel_;
182  pose_pub_.publish(p);
183 
184  // Figure out (and publish) the color underneath the turtle
185  {
186  Color color;
187  QRgb pixel = path_image.pixel((pos_ * meter_).toPoint());
188  color.r = qRed(pixel);
189  color.g = qGreen(pixel);
190  color.b = qBlue(pixel);
191  color_pub_.publish(color);
192  }
193 
194  ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f", nh_.getNamespace().c_str(), pos_.x(), pos_.y(), orient_);
195 
196  if (orient_ != old_orient)
197  {
198  rotateImage();
199  modified = true;
200  }
201  if (pos_ != old_pos)
202  {
203  if (pen_on_)
204  {
205  path_painter.setPen(pen_);
206  path_painter.drawLine(pos_ * meter_, old_pos * meter_);
207  }
208  modified = true;
209  }
210 
211  return modified;
212 }
213 
214 void Turtle::paint(QPainter& painter)
215 {
216  QPointF p = pos_ * meter_;
217  p.rx() -= 0.5 * turtle_rotated_image_.width();
218  p.ry() -= 0.5 * turtle_rotated_image_.height();
219  painter.drawImage(p, turtle_rotated_image_);
220 }
221 
222 }
turtlesim::Turtle::velocityCallback
void velocityCallback(const geometry_msgs::Twist::ConstPtr &vel)
Definition: turtle.cpp:67
turtlesim::Turtle::teleportRelativeCallback
bool teleportRelativeCallback(turtlesim::TeleportRelative::Request &, turtlesim::TeleportRelative::Response &)
Definition: turtle.cpp:93
turtlesim
Definition: turtle.h:53
turtlesim::Turtle::teleportAbsoluteCallback
bool teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request &, turtlesim::TeleportAbsolute::Response &)
Definition: turtle.cpp:99
turtlesim::Turtle::last_command_time_
ros::WallTime last_command_time_
Definition: turtle.h:92
turtlesim::Turtle::Turtle
Turtle(const ros::NodeHandle &nh, const QImage &turtle_image, const QPointF &pos, float orient)
Definition: turtle.cpp:42
turtlesim::Turtle::turtle_rotated_image_
QImage turtle_rotated_image_
Definition: turtle.h:74
turtlesim::Turtle::lin_vel_y_
qreal lin_vel_y_
Definition: turtle.h:80
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
turtlesim::Turtle::orient_
qreal orient_
Definition: turtle.h:77
turtlesim::Turtle::TeleportRequest::relative
bool relative
Definition: turtle.h:108
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
DEFAULT_PEN_R
#define DEFAULT_PEN_R
Definition: turtle.cpp:35
turtlesim::Turtle::set_pen_srv_
ros::ServiceServer set_pen_srv_
Definition: turtle.h:88
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
DEFAULT_PEN_B
#define DEFAULT_PEN_B
Definition: turtle.cpp:37
turtlesim::Turtle::teleport_absolute_srv_
ros::ServiceServer teleport_absolute_srv_
Definition: turtle.h:90
turtlesim::Turtle::ang_vel_
qreal ang_vel_
Definition: turtle.h:81
ROS_DEBUG
#define ROS_DEBUG(...)
turtlesim::Turtle::TeleportRequest::pos
QPointF pos
Definition: turtle.h:105
turtlesim::Turtle::TeleportRequest::linear
qreal linear
Definition: turtle.h:107
turtle.h
ros::WallTime::now
static WallTime now()
turtlesim::Turtle::TeleportRequest::theta
qreal theta
Definition: turtle.h:106
turtlesim::Turtle::pen_
QPen pen_
Definition: turtle.h:83
turtlesim::Turtle::pen_on_
bool pen_on_
Definition: turtle.h:82
turtlesim::Turtle::rotateImage
void rotateImage()
Definition: turtle.cpp:105
turtlesim::Turtle::velocity_sub_
ros::Subscriber velocity_sub_
Definition: turtle.h:85
ROS_WARN
#define ROS_WARN(...)
turtlesim::Turtle::teleport_requests_
V_TeleportRequest teleport_requests_
Definition: turtle.h:111
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
turtlesim::Turtle::meter_
float meter_
Definition: turtle.h:94
turtlesim::Turtle::turtle_image_
QImage turtle_image_
Definition: turtle.h:73
turtlesim::Turtle::update
bool update(double dt, QPainter &path_painter, const QImage &path_image, qreal canvas_width, qreal canvas_height)
Definition: turtle.cpp:112
turtlesim::Turtle::setPenCallback
bool setPenCallback(turtlesim::SetPen::Request &, turtlesim::SetPen::Response &)
Definition: turtle.cpp:75
turtlesim::Turtle::paint
void paint(QPainter &painter)
Definition: turtle.cpp:214
turtlesim::Turtle::pose_pub_
ros::Publisher pose_pub_
Definition: turtle.h:86
turtlesim::Turtle::lin_vel_x_
qreal lin_vel_x_
Definition: turtle.h:79
turtlesim::Turtle::TeleportRequest
Definition: turtle.h:96
PI
#define PI
Definition: turtle.h:51
turtlesim::Turtle::teleport_relative_srv_
ros::ServiceServer teleport_relative_srv_
Definition: turtle.h:89
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ros::WallDuration
turtlesim::Turtle::nh_
ros::NodeHandle nh_
Definition: turtle.h:71
DEFAULT_PEN_G
#define DEFAULT_PEN_G
Definition: turtle.cpp:36
turtlesim::Turtle::pos_
QPointF pos_
Definition: turtle.h:76
ros::NodeHandle
turtlesim::Turtle::color_pub_
ros::Publisher color_pub_
Definition: turtle.h:87


turtlesim
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Apr 12 2025 02:28:03