Runtime issues caused by locale-dependent double parsing
Here is a comment pointing out runtime issues depending on locale settings: https://github.com/ros-planning/moveit2/issues/1782#issuecomment-1385826225
Problem
Locale settings define the format for different things, in particular LC_NUMERIC defines how decimal numbers are represented. Usually, we use dot notation for all configs (say XML), but if the system or application (like Qt) uses a locale with comma-separated decimals, double parsing with std::stod will silently cut off the decimals causing confusing issues depending on where it occurs.
Here is the same issue in urdfdom from a couple years ago: https://github.com/ros/urdfdom/issues/98
Solution I suggest switching to std::from_chars which always uses dot notation. See https://github.com/ros-controls/ros2_control/pull/921 for an example PR.
Some commonly used packages affected (searching for "stod", there are also other variants like "stof"):
- ros-planning
- moveit2
- https://github.com/ros-planning/moveit2/blob/main/moveit_planners/pilz_industrial_motion_planner_testutils/include/pilz_industrial_motion_planner_testutils/xml_testdata_loader.h#L214
- https://github.com/ros-planning/moveit2/blob/main/moveit_core/robot_state/src/conversions.cpp#L569
- https://github.com/ros-planning/moveit2/blob/main/moveit_core/robot_model/src/robot_model.cpp#L1057
- https://github.com/ros-planning/moveit2/blob/main/moveit_core/robot_model/src/robot_model.cpp#L1128
- srdfdom
- https://github.com/ros-planning/srdfdom/blob/ros2/src/model.cpp#L477
- moveit2
- ros_controls
- https://github.com/ros-controls/ros2_control/pull/921
- Several others, see https://github.com/search?q=org%3Aros-controls+std%3A%3Astod&type=Code
- ros2
- geometry2 https://github.com/ros2/geometry2/blob/rolling/tf2_ros/src/static_transform_broadcaster_program.cpp#L73
- PickNikRobotics
- ro2_robotiq_gripper https://github.com/PickNikRobotics/ros2_robotiq_gripper/blob/main/robotiq_driver/src/hardware_interface.cpp#L62
- UniversalRobots
- Universal_Robots_ROS2_Driver https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/src/hardware_interface.cpp
PRs very welcome, and please tag this issue to prevent duplicate work ;)
The <charconv> header has been notoriously one of the last bits of C++17 to get implemented so I worry that we're going to have portability issues if we use it, particular using it for floats which has taken longer to implement than the equivalent integer utilities. It's worth trying, but be forewarned.
This has bitten OMPL in the past, too. We worked around it like this.
The
<charconv>header has been notoriously one of the last bits of C++17 to get implemented so I worry that we're going to have portability issues if we use it, particular using it for floats which has taken longer to implement that the equivalent integer utilities. It's worth trying, but be forewarned.
What kind of portability issues do you mean and would you have a better alternative? I'm not a big fan of using stringstream here or temporarily switching locales.
What kind of portability issues
The fact that it's taken longer than any other C++17 feature to implement means some platforms or compilers with "complete C++17 support" sometimes come with a caveat about imperfect or incomplete <charconv> support.
I don't have any better alternatives, sorry. We just have to do our homework to figure out if all the platforms/compilers/standard libraries we support already implement this.
We just have to do our homework to figure out if all the platforms/compilers/standard libraries we support
Is it working on Ubuntu 22.04 with the default gcc and clang versions? If so, then that seems good enough. We are not offering support for Windows or backporting this.
Is it working on Ubuntu 22.04 with the default gcc and clang versions? If so, then that seems good enough. We are not offering support for Windows or backporting this.
so this is something I would clearly consider a bug / broken functionality, and you're proposing to leave it broken for non-Humble/Rolling releases?
I'm suggesting that we don't have to debate the solution of using <charconv> if we don't consider backporting that fix. If we do want this thing to be portable and back-portable, then maybe we consider something else. :shrug:
I'm somewhat confused why nobody mentioned https://github.com/ros-planning/moveit/pull/1099 . We had these issues before in MoveIt and @simonschmeisser implemented utility functions just for this...
History tends to repeat itself ...
https://github.com/ros-planning/moveit2/blob/c8df8cc2f5ddf13512b677cc795db556a3ec9d3f/moveit_core/utils/include/moveit/utils/lexical_casts.h#L62
is what we came up with back then.
For urdfdom I came up with a locale dependent unit test which could in theory be used to test compatibility of
https://github.com/ros/urdfdom/blob/41838e1f3623e0538a402024b76f296dbbcbed9f/urdf_parser/test/CMakeLists.txt#L48
For some reason I didn't make the connection to lexical_casts, even though I knew about it... It's concerning that this bug is still around and has even raised children. It's all over the place and I think there are even some in ROS 1 which I was planning to look at next.
I took care of srdfdom: https://github.com/ros-planning/srdfdom/pull/108
This issue is being labeled as stale because it has been open 45 days with no activity. It will be automatically closed after another 45 days without follow-ups.
This issue was closed because it has been stalled for 45 days with no activity.