Skip to content

Commit

Permalink
Fixes precision loss when adding nested models. (#314)
Browse files Browse the repository at this point in the history
* Fixes precision loss when adding nested models.

The precision loss is resolved by explicitly calling std::setprecision
for float and double parameters when these are streamed/requested as
strings.

Signed-off-by: Hauke Heibel <[email protected]>

* fixed codecheck errors

Signed-off-by: Jenn Nguyen <[email protected]>

Co-authored-by: Jenn Nguyen <[email protected]>
Co-authored-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
3 people authored Feb 4, 2021
1 parent a390765 commit 28124b0
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 6 deletions.
16 changes: 16 additions & 0 deletions include/sdf/Param.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include <cctype>
#include <cstdint>
#include <functional>
#include <iomanip>
#include <limits>
#include <memory>
#include <optional>
#include <sstream>
Expand Down Expand Up @@ -79,6 +81,20 @@ namespace sdf
return os;
}

template<>
inline std::ostream& operator<<(std::ostream &os, ParamStreamer<double> s)
{
os << std::setprecision(std::numeric_limits<double>::max_digits10) << s.val;
return os;
}

template<>
inline std::ostream& operator<<(std::ostream &os, ParamStreamer<float> s)
{
os << std::setprecision(std::numeric_limits<float>::max_digits10) << s.val;
return os;
}

template<class... Ts>
std::ostream& operator<<(std::ostream& os,
ParamStreamer<std::variant<Ts...>> sv)
Expand Down
4 changes: 2 additions & 2 deletions test/integration/model/test_model_with_frames/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,15 @@
<pose relative_to="F2"/>
<geometry>
<sphere>
<radius>1</radius>
<radius>1.5707963267948966</radius>
</sphere>
</geometry>
</visual>
<collision name="C1">
<pose relative_to="__model__"/>
<geometry>
<sphere>
<radius>1</radius>
<radius>0.78539816339744828</radius>
</sphere>
</geometry>
</collision>
Expand Down
4 changes: 2 additions & 2 deletions test/integration/nested_model_with_frames_expected.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,15 @@
<pose relative_to='F2'>0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>1</radius>
<radius>1.5707963267948966</radius>
</sphere>
</geometry>
</visual>
<collision name='C1'>
<pose relative_to='__model__'>0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>1</radius>
<radius>0.78539816339744828</radius>
</sphere>
</geometry>
</collision>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,15 @@
<pose relative_to='F2'>0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>1</radius>
<radius>1.5707963267948966</radius>
</sphere>
</geometry>
</visual>
<collision name='C1'>
<pose relative_to='__model__'>0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>1</radius>
<radius>0.78539816339744828</radius>
</sphere>
</geometry>
</collision>
Expand Down

0 comments on commit 28124b0

Please sign in to comment.