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

Fix duration bug and add tests. #98

Merged
merged 1 commit into from Jan 26, 2019
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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
7 changes: 5 additions & 2 deletions rostime/include/ros/impl/duration.h
Expand Up @@ -63,11 +63,14 @@ namespace ros {
template<class T>
T& DurationBase<T>::fromNSec(int64_t t)
{
int64_t sec64 = t / 1000000000;
int64_t sec64 = t / 1000000000LL;
if (sec64 < INT_MIN || sec64 > INT_MAX)
throw std::runtime_error("Duration is out of dual 32-bit range");
sec = (int32_t)sec64;
nsec = (int32_t)(t % 1000000000);
nsec = (int32_t)(t % 1000000000LL);

normalizeSecNSecSigned(sec, nsec);

return *static_cast<T*>(this);
}

Expand Down
22 changes: 22 additions & 0 deletions rostime/test/time.cpp
Expand Up @@ -415,6 +415,21 @@ TEST(Duration, ToFromSec)
EXPECT_EQ(ros::Duration(-0.5), ros::Duration(0, -500000000LL));
}

TEST(Duration, FromNSec)
{
ros::Duration t;
t.fromNSec(-500000000LL);
EXPECT_EQ(ros::Duration(-0.5), t);

t.fromNSec(-1500000000LL);
EXPECT_EQ(ros::Duration(-1.5), t);

t.fromNSec(500000000LL);
EXPECT_EQ(ros::Duration(0.5), t);

t.fromNSec(1500000000LL);
EXPECT_EQ(ros::Duration(1.5), t);
}

TEST(Duration, OperatorPlus)
{
Expand Down Expand Up @@ -448,6 +463,13 @@ TEST(Duration, OperatorMinus)

}

ros::Time t1(1.1);
ros::Time t2(1.3);
ros::Duration time_diff = t1 - t2; //=-0.2

EXPECT_NEAR(time_diff.toSec(), -0.2, epsilon);
EXPECT_LE(time_diff, ros::Duration(-0.19));
EXPECT_GE(time_diff, ros::Duration(-0.21));
}

TEST(Duration, OperatorTimes)
Expand Down