ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ros::Time::isValid doesn't do what we think it does?

asked 2019-06-24 13:09:53 -0500

ivaughn_whoi gravatar image

From the documentation (http://docs.ros.org/melodic/api/rosti...), ros::Time::isValid returns "whether or not the current time is valid. Time is valid if it is non-zero".

However, a trivial example is enough to show that the implementation does not do this:

#include <ros/ros.h>

int main(int argc, char** argv) {
    ros::init(argc, argv, "rostime_example");
    ros::NodeHandle n;

    // default construct a time
    ros::Time t;

    ROS_WARN_STREAM("time value: " <<t.toSec());
    ROS_WARN_STREAM("time valid: " <<t.isValid());

    return 0;
}

The output is:

ivaughn@ros-pc:~/test_ws$ rosrun rostime_example node 
[ WARN] [1561399516.961348750]: time value: 0
[ WARN] [1561399516.961420491]: time valid: 1

Any idea what's going on here? Is this just a bug in ROS 1, or am I misunderstanding how this function is expected to behave.

We're kind of curious, behavior that does something different when a timestamp is invalid is often safety-critical. Thanks!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-06-24 13:22:31 -0500

gvdhoorn gravatar image

updated 2019-06-24 13:33:04 -0500

I believe this is due to a misunderstanding of the comment on isValid().

The documentation indeed states (here):

Returns whether or not the current time is valid. Time is valid if it is non-zero.

But "the [..] time" it refers to is not the Time instance, but "the time", as in: the global ROS time.

A ROS node can use different methods to retrieve the "current time": it can use walltime, a simulation time or something else. The "valid" here essentially returns true whenever one of those sources have been selected and has been initialised properly.

0 is chosen as a sentinel value to detect when that is not the case (as it's assumed that 0 is just not a valid value for any source of time (whether that is correct is something else)).

It's slightly confusing that a ros::Time instance can also have a 0 value and that ros::Time::isValid() is a static method of the ros::Time class.

In the code that you show:

int main(int argc, char** argv) {
    ros::init(argc, argv, "rostime_example");
    [..]
}

isValid() will return true as soon as you call ros::init(..) (as one of its duties is to initialise the time subsystem).


We can also take a look at the sources (from here):

bool Time::isValid()
{
  return (!g_use_sim_time) || !g_sim_time.isZero();
}

This essentially tells us that "time" is considered "valid" if either we're not using simulation time, or, if simulation time is being used, it's != 0.

The g_ prefixes tell us that this static method is checking globals, not ros::Time member variables.


Edit: perhaps a nice contribution would be to improve the documentation of this method and to remove the ambiguity.

edit flag offensive delete link more

Comments

And this is not directed at you, but:

Is this just a bug in ROS 1, [..]

I like how posters here often insert these sort of statements almost casually in their questions.

gvdhoorn gravatar image gvdhoorn  ( 2019-06-24 13:42:24 -0500 )edit

Yeah, I'd like to make sure I correctly understand what's going on before claiming its a bug. WIth ROS its more likely to be a documentation issue than anything else.

Pull request: https://github.com/ros/roscpp_core/pu...

ivaughn_whoi gravatar image ivaughn_whoi  ( 2019-06-24 14:13:55 -0500 )edit
0

answered 2022-02-11 07:54:23 -0500

Micha Sende gravatar image

As the answer by @gvdhoorn pointed out, isValid is a static function and not related to your time instance.

To get the result you expected, you should change your code to:

#include <ros/ros.h>

int main(int argc, char** argv) {
    ros::init(argc, argv, "rostime_example");
    ros::NodeHandle n;

    // default construct a time
    ros::Time t;

    ROS_WARN_STREAM("time value: " <<t.toSec());
    ROS_WARN_STREAM("time valid: " <<t.isZero()==false);

    return 0;
}
edit flag offensive delete link more

Question Tools

Stats

Asked: 2019-06-24 13:09:53 -0500

Seen: 1,139 times

Last updated: Feb 11 '22