Class Stopwatch

Class Documentation

class Stopwatch

The stopwatch accepts an rclcpp::Clock instance from a rclcpp::Node (allowing use of sim time if use_sim_time set in node). Keeps track of time spent in the run state, accessed through ElapsedRunTime(), and time spent in the stop state, accessed through ElapsedStopTime(). Elapsed run time starts accumulating after the first call to Start(). Elapsed stop time starts accumulation after Start() has been called followed by Stop(). The stopwatch can be reset with the Reset() function.

Example usage

ros_gz_sim::Stopwatch watch;
watch.Start();

// do something...

std::cout << "Elapsed time is "
<< std::chrono::duration_cast<std::chrono::milliseconds>(
  timeSys.ElapsedRunTime()).count() << " ms\n";
watch.Stop();

Public Functions

Stopwatch()

Constructor.

Stopwatch(const Stopwatch &_watch)

Copy constructor.

Parameters:

_watch[in] The stop watch to copy.

Stopwatch(Stopwatch &&_watch) noexcept

Move constructor.

Parameters:

_watch[in] The stop watch to move.

virtual ~Stopwatch()

Destructor.

void SetClock(rclcpp::Clock::SharedPtr _clock)

Take a clock instance (e.g. get_clock() from rclcpp::Node). Can also follow sim time on /clock when node’s use_sim_time param is set param[in] _clock.

bool Start(const bool _reset = false)

Start the stopwatch.

Parameters:

_reset[in] If true the stopwatch is reset first.

Returns:

True if the the stopwatch was started. This will return false if the stopwatch was already running.

const rclcpp::Time &StartTime() const

Get the time when the stopwatch was started.

Returns:

The time when stopwatch was started, or std::chrono::steady_clock::time_point::min() if the stopwatch has not been started.

bool Stop()

Stop the stopwatch.

Returns:

True if the stopwatch was stopped. This will return false if the stopwatch is not running.

const rclcpp::Time &StopTime() const

Get the time when the stopwatch was last stopped.

Returns:

The time when stopwatch was last stopped, or std::chrono::steady_clock::time_point::min() if the stopwatch has never been stopped.

bool Running() const

Get whether the stopwatch is running.

Returns:

True if the stopwatch is running.

void Reset()

Reset the stopwatch. This resets the start time, stop time, elapsed duration and elapsed stop duration.

rclcpp::Duration ElapsedRunTime() const

Get the amount of time that the stop watch has been running. This is the total amount of run time, spannning all start and stop calls. The Reset function or passing true to the Start function will reset this value.

Returns:

Total amount of elapsed run time.

rclcpp::Duration ElapsedStopTime() const

Get the amount of time that the stop watch has been stopped. This is the total amount of stop time, spannning all start and stop calls. The Reset function or passing true to the Start function will reset this value.

Returns:

Total amount of elapsed stop time.

bool operator==(const Stopwatch &_watch) const

Equality operator.

Parameters:

_watch[in] The watch to compare.

Returns:

True if this watch equals the provided watch.

bool operator!=(const Stopwatch &_watch) const

Inequality operator.

Parameters:

_watch[in] The watch to compare.

Returns:

True if this watch does not equal the provided watch.

Stopwatch &operator=(const Stopwatch &_watch)

Copy assignment operator.

Parameters:

_watch[in] The stop watch to copy.

Returns:

Reference to this.

Stopwatch &operator=(Stopwatch &&_watch)

Move assignment operator.

Parameters:

_watch[in] The stop watch to move.

Returns:

Reference to this.