Skip to content

Commit 2fb7b9f

Browse files
zhoulaifudirk-thomas
authored andcommitted
sin(x+pi/2)-> cos(x); cos(x+pi/2)->-sin(x) in turtle.cpp. Fixing ros#47 (ros#51)
1 parent f454866 commit 2fb7b9f

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

turtlesim/src/turtle.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -123,8 +123,8 @@ bool Turtle::update(double dt, QPainter& path_painter, const QImage& path_image,
123123
if (req.relative)
124124
{
125125
orient_ += req.theta;
126-
pos_.rx() += std::sin(orient_ + PI/2.0) * req.linear;
127-
pos_.ry() += std::cos(orient_ + PI/2.0) * req.linear;
126+
pos_.rx() += std::cos(orient_) * req.linear;
127+
pos_.ry() += - std::sin(orient_) * req.linear;
128128
}
129129
else
130130
{
@@ -154,8 +154,8 @@ bool Turtle::update(double dt, QPainter& path_painter, const QImage& path_image,
154154
orient_ = orient_ + ang_vel_ * dt;
155155
// Keep orient_ between -pi and +pi
156156
orient_ -= 2*PI * std::floor((orient_ + PI)/(2*PI));
157-
pos_.rx() += std::sin(orient_ + PI/2.0) * lin_vel_ * dt;
158-
pos_.ry() += std::cos(orient_ + PI/2.0) * lin_vel_ * dt;
157+
pos_.rx() += std::cos(orient_) * lin_vel_ * dt;
158+
pos_.ry() += - std::sin(orient_) * lin_vel_ * dt;
159159

160160
// Clamp to screen size
161161
if (pos_.x() < 0 || pos_.x() > canvas_width ||

0 commit comments

Comments
 (0)