35 #define DEFAULT_PEN_R 0xb3 36 #define DEFAULT_PEN_G 0xb8 37 #define DEFAULT_PEN_B 0xff 44 , turtle_image_(turtle_image)
81 QPen pen(QColor(req.r, req.g, req.b));
84 pen.setWidth(req.width);
105 QTransform transform;
106 transform.rotate(-
orient_ * 180.0 /
PI + 90.0);
110 bool Turtle::update(
double dt, QPainter& path_painter,
const QImage& path_image, qreal canvas_width, qreal canvas_height)
112 bool modified =
false;
118 for (; it != end; ++it)
122 QPointF old_pos =
pos_;
132 pos_.setY(std::max(0.0, static_cast<double>(canvas_height - req.
pos.y())));
138 path_painter.setPen(
pen_);
139 path_painter.drawLine(
pos_ *
meter_, old_pos * meter_);
152 QPointF old_pos =
pos_;
161 if (
pos_.x() < 0 ||
pos_.x() > canvas_width ||
162 pos_.y() < 0 ||
pos_.y() > canvas_height)
164 ROS_WARN(
"Oh no! I hit the wall! (Clamping from [x=%f, y=%f])",
pos_.x(),
pos_.y());
167 pos_.setX(std::min(std::max(static_cast<double>(
pos_.x()), 0.0),
static_cast<double>(canvas_width)));
168 pos_.setY(std::min(std::max(static_cast<double>(
pos_.y()), 0.0),
static_cast<double>(canvas_height)));
173 p.y = canvas_height -
pos_.y();
182 QRgb pixel = path_image.pixel((
pos_ *
meter_).toPoint());
183 color.r = qRed(pixel);
184 color.g = qGreen(pixel);
185 color.b = qBlue(pixel);
200 path_painter.setPen(
pen_);
201 path_painter.drawLine(
pos_ *
meter_, old_pos * meter_);
ros::Subscriber velocity_sub_
bool teleportAbsoluteCallback(turtlesim::TeleportAbsolute::Request &, turtlesim::TeleportAbsolute::Response &)
ros::ServiceServer set_pen_srv_
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool update(double dt, QPainter &path_painter, const QImage &path_image, qreal canvas_width, qreal canvas_height)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
QImage turtle_rotated_image_
void velocityCallback(const geometry_msgs::Twist::ConstPtr &vel)
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool teleportRelativeCallback(turtlesim::TeleportRelative::Request &, turtlesim::TeleportRelative::Response &)
ros::WallTime last_command_time_
Turtle(const ros::NodeHandle &nh, const QImage &turtle_image, const QPointF &pos, float orient)
ros::ServiceServer teleport_relative_srv_
ros::ServiceServer teleport_absolute_srv_
V_TeleportRequest teleport_requests_
ros::Publisher color_pub_
void paint(QPainter &painter)
bool setPenCallback(turtlesim::SetPen::Request &, turtlesim::SetPen::Response &)