ros_tutorials
ros_tutorials copied to clipboard
[ros2 turtlesim] normalizeAngle takes double-sized data as float
Hi.
In turtle.cpp
for ros2 turtlesim, normalizeAngle
takes a float
as an argument.
However, the data passed into the function is of size double
when the function is called, and gets truncated to become nan
.
...
ang_vel_ = vel->angular.z; // type of geometry_msgs::msg::Twist.angular.z is float64 (double)
...
orient_ = orient_ + ang_vel_ * dt; // orient_ is of type qreal, which is double
orient_ = normalizeAngle(orient_); // double-sized data gets truncated to nan
When a control program publishes to /cmd_vel
a Twist message in which angular.z
is set to a double
-sized value, normalizeAngle
ends up returning nan
. As a result, orient_
becomes nan
, and accordingly, theta
, x
, y
of the turtle's Pose becomes nan
in the subsequent lines. This effectively removes the turtle from the frame. The "clamping" logic fails to put the turtle back in the frame, as it compares nan
with integers.
e.g., Published message:
geometry_msgs.msg.Twist(
linear=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=0.0),
angular=geometry_msgs.msg.Vector3(x=0.0, y=0.0, z=-4.0e+214)
)
Result:
Tested and confirmed on the foxy-devel
branch, but this problem affects all ros2 branches.