Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use double when handling qreal orient_ #114

Merged
merged 1 commit into from
Dec 20, 2021
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions turtlesim/src/turtle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
namespace turtlesim
{

static float normalizeAngle(float angle)
static double normalizeAngle(double angle)
{
return angle - (TWO_PI * std::floor((angle + PI) / (TWO_PI)));
}
Expand Down Expand Up @@ -206,8 +206,8 @@ bool Turtle::update(double dt, QPainter& path_painter, const QImage& path_image,
}
else
{
float theta = normalizeAngle(rotate_absolute_goal_handle_->get_goal()->theta);
float remaining = normalizeAngle(theta - static_cast<float>(orient_));
double theta = normalizeAngle(rotate_absolute_goal_handle_->get_goal()->theta);
double remaining = normalizeAngle(theta - static_cast<float>(orient_));

// Update result
rotate_absolute_result_->delta = normalizeAngle(static_cast<float>(rotate_absolute_start_orient_ - orient_));
Expand Down