Skip to content

Commit

Permalink
Using std::chrono instead of common::Time (#116)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
Signed-off-by: Louise Poubel <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Sep 11, 2020
1 parent 24c75f5 commit 40a4658
Show file tree
Hide file tree
Showing 7 changed files with 39 additions and 28 deletions.
11 changes: 0 additions & 11 deletions .github/ci-bionic/after_make.sh

This file was deleted.

5 changes: 0 additions & 5 deletions .github/ci-bionic/dependencies.yaml

This file was deleted.

2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ ign_find_package(TINYXML2 REQUIRED PRIVATE PRETTY tinyxml2)

#--------------------------------------
# Find ignition-math
ign_find_package(ignition-math6 REQUIRED)
ign_find_package(ignition-math6 REQUIRED VERSION 6.5)
set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR})

#--------------------------------------
Expand Down
7 changes: 7 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,13 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition GUI 3.x to 4.x

* Use rendering4, transport9 and msgs6.
* Deprecated `ignition::gui::convert` to `ignition::common::Time`.
Use `ignition::msgs::Convert` to `std::chrono::steady_clock::time_point`
instead.

## Ignition GUI 2.x to 3.x

* Use rendering3, transport8 and msgs5.
Expand Down
6 changes: 6 additions & 0 deletions include/ignition/gui/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -90,13 +90,19 @@ namespace ignition
/// \brief Convert an ignition::msgs::Time to an ignition::common::Time
/// \param[in] _t The time to convert
/// \return An ignition::common::Time object
/// \deprecated Use ignition::msgs:Convert to
/// std::chrono::steady_clock::time_point
IGNITION_GUI_VISIBLE
IGN_DEPRECATED(4)
common::Time convert(const msgs::Time &_t);

/// \brief Convert an ignition::common::Time to an ignition::msgs::Time
/// \param[in] _t The time to convert
/// \return An ignition::msgs::Time object
/// \deprecated Use ignition::msgs:Convert to
/// std::chrono::steady_clock::time_point
IGNITION_GUI_VISIBLE
IGN_DEPRECATED(4)
msgs::Time convert(const common::Time &_t);
}
}
Expand Down
15 changes: 14 additions & 1 deletion src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -159,16 +159,29 @@ TEST(ConversionsTest, Time)
ignition::msgs::Time t;
t.set_sec(s);
t.set_nsec(ns);

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
auto nt = convert(convert(t));
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
EXPECT_DOUBLE_EQ(nt.sec(), t.sec());
EXPECT_DOUBLE_EQ(nt.nsec(), t.nsec());
}

// Common to msgs to common
{
common::Time t(s, ns);
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif
EXPECT_EQ(convert(convert(t)), t);
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
}
}

21 changes: 11 additions & 10 deletions src/plugins/world_stats/WorldStats.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@

#include <ignition/common/Console.hh>
#include <ignition/common/StringUtils.hh>
#include <ignition/common/Time.hh>
#include <ignition/plugin/Register.hh>

#include "ignition/gui/Helpers.hh"
Expand Down Expand Up @@ -183,22 +182,24 @@ void WorldStats::ProcessMsg()
{
std::lock_guard<std::recursive_mutex> lock(this->dataPtr->mutex);

ignition::common::Time time;
std::chrono::steady_clock::time_point timePoint;

if (this->dataPtr->msg.has_sim_time())
{
time.sec = this->dataPtr->msg.sim_time().sec();
time.nsec = this->dataPtr->msg.sim_time().nsec();

this->SetSimTime(QString::fromStdString(time.FormattedString()));
timePoint = math::secNsecToTimePoint(
this->dataPtr->msg.sim_time().sec(),
this->dataPtr->msg.sim_time().nsec());
this->SetSimTime(QString::fromStdString(
math::timePointToString(timePoint)));
}

if (this->dataPtr->msg.has_real_time())
{
time.sec = this->dataPtr->msg.real_time().sec();
time.nsec = this->dataPtr->msg.real_time().nsec();

this->SetRealTime(QString::fromStdString(time.FormattedString()));
timePoint = math::secNsecToTimePoint(
this->dataPtr->msg.real_time().sec(),
this->dataPtr->msg.real_time().nsec());
this->SetRealTime(QString::fromStdString(
math::timePointToString(timePoint)));
}

{
Expand Down

0 comments on commit 40a4658

Please sign in to comment.