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

Avoid to use std::to_string to pass floating point simulation parameters #246

Merged
merged 2 commits into from
Sep 27, 2020
Merged
Show file tree
Hide file tree
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
28 changes: 25 additions & 3 deletions cpp/scenario/gazebo/src/helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include <sdf/World.hh>

#include <cassert>
#include <sstream>

using namespace scenario::gazebo;

Expand Down Expand Up @@ -335,6 +336,27 @@ bool utils::renameSDFModel(sdf::Root& sdfRoot,
return true;
}

namespace scenario::gazebo::utils {
/**
* Convert a double to a string ignoring the current locale.
*
* Furthermore, set it with precision 25 to ensure that the
* string can be converted back exactly to the double that
* generated it.
*/
std::string toExactStringNoLocale(const double in);
}


std::string utils::toExactStringNoLocale(const double in)
{
std::ostringstream ss;
ss.imbue(std::locale::classic());
ss << std::setprecision(25) << in;
return ss.str();
}


bool utils::updateSDFPhysics(sdf::Root& sdfRoot,
const double maxStepSize,
const double rtf,
Expand Down Expand Up @@ -372,16 +394,16 @@ bool utils::updateSDFPhysics(sdf::Root& sdfRoot,
assert(physicsElement);

sdf::ElementPtr max_step_size = physicsElement->GetElement("max_step_size");
max_step_size->AddValue("double", std::to_string(maxStepSize), true);
max_step_size->AddValue("double", toExactStringNoLocale(maxStepSize), true);

sdf::ElementPtr real_time_update_rate =
physicsElement->GetElement("real_time_update_rate");
real_time_update_rate->AddValue(
"double", std::to_string(realTimeUpdateRate), true);
"double", toExactStringNoLocale(realTimeUpdateRate), true);

sdf::ElementPtr real_time_factor =
physicsElement->GetElement("real_time_factor");
real_time_factor->AddValue("double", std::to_string(rtf), true);
real_time_factor->AddValue("double", toExactStringNoLocale(rtf), true);

return true;
}
Expand Down
4 changes: 2 additions & 2 deletions tests/test_scenario/test_world.py
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ def test_world_physics_plugin(gazebo: scenario.GazeboSimulator):


@pytest.mark.parametrize("gazebo",
[(0.001, 1.0, 1)],
[(0.001, 1.0, 1), (1e-9, 1.0, 1)],
indirect=True,
ids=utils.id_gazebo_fn)
def test_sim_time_starts_from_zero(gazebo: scenario.GazeboSimulator):
Expand All @@ -207,4 +207,4 @@ def test_sim_time_starts_from_zero(gazebo: scenario.GazeboSimulator):
assert world.time() == 2 * dt

gazebo.run(paused=False)
assert world.time() == 3 * dt
assert world.time() == pytest.approx(3 * dt)