$search
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.h" 00031 00032 #include <wx/wx.h> 00033 00034 #define DEFAULT_PEN_R 0xb3 00035 #define DEFAULT_PEN_G 0xb8 00036 #define DEFAULT_PEN_B 0xff 00037 00038 namespace turtlesim 00039 { 00040 00041 Turtle::Turtle(const ros::NodeHandle& nh, const wxImage& turtle_image, const Vector2& pos, float orient) 00042 : nh_(nh) 00043 , turtle_image_(turtle_image) 00044 , pos_(pos) 00045 , orient_(orient) 00046 , lin_vel_(0.0) 00047 , ang_vel_(0.0) 00048 , pen_on_(true) 00049 , pen_(wxColour(DEFAULT_PEN_R, DEFAULT_PEN_G, DEFAULT_PEN_B)) 00050 { 00051 pen_.SetWidth(3); 00052 turtle_ = wxBitmap(turtle_image_); 00053 00054 velocity_sub_ = nh_.subscribe("command_velocity", 1, &Turtle::velocityCallback, this); 00055 pose_pub_ = nh_.advertise<Pose>("pose", 1); 00056 color_pub_ = nh_.advertise<Color>("color_sensor", 1); 00057 set_pen_srv_ = nh_.advertiseService("set_pen", &Turtle::setPenCallback, this); 00058 teleport_relative_srv_ = nh_.advertiseService("teleport_relative", &Turtle::teleportRelativeCallback, this); 00059 teleport_absolute_srv_ = nh_.advertiseService("teleport_absolute", &Turtle::teleportAbsoluteCallback, this); 00060 00061 meter_ = turtle_.GetHeight(); 00062 } 00063 00064 00065 void Turtle::velocityCallback(const VelocityConstPtr& vel) 00066 { 00067 last_command_time_ = ros::WallTime::now(); 00068 lin_vel_ = vel->linear; 00069 ang_vel_ = vel->angular; 00070 } 00071 00072 bool Turtle::setPenCallback(turtlesim::SetPen::Request& req, turtlesim::SetPen::Response&) 00073 { 00074 pen_on_ = !req.off; 00075 if (req.off) 00076 { 00077 return true; 00078 } 00079 00080 wxPen pen(wxColour(req.r, req.g, req.b)); 00081 if (req.width != 0) 00082 { 00083 pen.SetWidth(req.width); 00084 } 00085 00086 pen_ = pen; 00087 return true; 00088 } 00089 00090 bool Turtle::teleportRelativeCallback(turtlesim::TeleportRelative::Request& req, turtlesim::TeleportRelative::Response&) 00091 { 00092 teleport_requests_.push_back(TeleportRequest(0, 0, req.angular, req.linear, true)); 00093 return true; 00094 } 00095 00096 bool Turtle::teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request& req, turtlesim::TeleportAbsolute::Response&) 00097 { 00098 teleport_requests_.push_back(TeleportRequest(req.x, req.y, req.theta, 0, false)); 00099 return true; 00100 } 00101 00102 void Turtle::update(double dt, wxMemoryDC& path_dc, const wxImage& path_image, wxColour background_color, float canvas_width, float canvas_height) 00103 { 00104 // first process any teleportation requests, in order 00105 V_TeleportRequest::iterator it = teleport_requests_.begin(); 00106 V_TeleportRequest::iterator end = teleport_requests_.end(); 00107 for (; it != end; ++it) 00108 { 00109 const TeleportRequest& req = *it; 00110 00111 Vector2 old_pos = pos_; 00112 if (req.relative) 00113 { 00114 orient_ += req.theta; 00115 pos_.x += sin(orient_ + PI/2.0) * req.linear; 00116 pos_.y += cos(orient_ + PI/2.0) * req.linear; 00117 } 00118 else 00119 { 00120 pos_.x = req.pos.x; 00121 pos_.y = std::max(0.0f, canvas_height - req.pos.y); 00122 orient_ = req.theta; 00123 } 00124 00125 path_dc.SetPen(pen_); 00126 path_dc.DrawLine(pos_.x * meter_, pos_.y * meter_, old_pos.x * meter_, old_pos.y * meter_); 00127 } 00128 00129 teleport_requests_.clear(); 00130 00131 if (ros::WallTime::now() - last_command_time_ > ros::WallDuration(1.0)) 00132 { 00133 lin_vel_ = 0.0f; 00134 ang_vel_ = 0.0f; 00135 } 00136 00137 Vector2 old_pos = pos_; 00138 00139 orient_ = fmod(orient_ + ang_vel_ * dt, 2*PI); 00140 pos_.x += sin(orient_ + PI/2.0) * lin_vel_ * dt; 00141 pos_.y += cos(orient_ + PI/2.0) * lin_vel_ * dt; 00142 00143 // Clamp to screen size 00144 if (pos_.x < 0 || pos_.x >= canvas_width 00145 || pos_.y < 0 || pos_.y >= canvas_height) 00146 { 00147 ROS_WARN("Oh no! I hit the wall! (Clamping from [x=%f, y=%f])", pos_.x, pos_.y); 00148 } 00149 00150 pos_.x = std::min(std::max(pos_.x, 0.0f), canvas_width); 00151 pos_.y = std::min(std::max(pos_.y, 0.0f), canvas_height); 00152 00153 int canvas_x = pos_.x * meter_; 00154 int canvas_y = pos_.y * meter_; 00155 00156 { 00157 wxImage rotated_image = turtle_image_.Rotate(orient_ - PI/2.0, wxPoint(turtle_image_.GetWidth() / 2, turtle_image_.GetHeight() / 2), false); 00158 00159 for (int y = 0; y < rotated_image.GetHeight(); ++y) 00160 { 00161 for (int x = 0; x < rotated_image.GetWidth(); ++x) 00162 { 00163 if (rotated_image.GetRed(x, y) == 255 && rotated_image.GetBlue(x, y) == 255 && rotated_image.GetGreen(x, y) == 255) 00164 { 00165 rotated_image.SetAlpha(x, y, 0); 00166 } 00167 } 00168 } 00169 00170 turtle_ = wxBitmap(rotated_image); 00171 } 00172 00173 Pose p; 00174 p.x = pos_.x; 00175 p.y = canvas_height - pos_.y; 00176 p.theta = orient_; 00177 p.linear_velocity = lin_vel_; 00178 p.angular_velocity = ang_vel_; 00179 pose_pub_.publish(p); 00180 00181 // Figure out (and publish) the color underneath the turtle 00182 { 00183 wxSize turtle_size = wxSize(turtle_.GetWidth(), turtle_.GetHeight()); 00184 Color color; 00185 color.r = path_image.GetRed(canvas_x, canvas_y); 00186 color.g = path_image.GetGreen(canvas_x, canvas_y); 00187 color.b = path_image.GetBlue(canvas_x, canvas_y); 00188 color_pub_.publish(color); 00189 } 00190 00191 ROS_DEBUG("[%s]: pos_x: %f pos_y: %f theta: %f", nh_.getNamespace().c_str(), pos_.x, pos_.y, orient_); 00192 00193 if (pen_on_) 00194 { 00195 if (pos_ != old_pos) 00196 { 00197 path_dc.SetPen(pen_); 00198 path_dc.DrawLine(pos_.x * meter_, pos_.y * meter_, old_pos.x * meter_, old_pos.y * meter_); 00199 } 00200 } 00201 } 00202 00203 void Turtle::paint(wxDC& dc) 00204 { 00205 wxSize turtle_size = wxSize(turtle_.GetWidth(), turtle_.GetHeight()); 00206 dc.DrawBitmap(turtle_, pos_.x * meter_ - (turtle_size.GetWidth() / 2), pos_.y * meter_ - (turtle_size.GetHeight() / 2), true); 00207 } 00208 00209 }