BipedalLocomotion::System::RosClock class final

RosClock implements the IClock interface using ros functions.

The clock can be easily used as follows

#include <BipedalLocomotion/System/Clock.h>
#include <BipedalLocomotion/System/RosClock.h>

#include <chrono>
#include <memory>

int main(int argc, char *argv[])
{
   // Change the clock
   BipedalLocomotion::System::ClockBuilder::setFactory(std::make_shared<BipedalLocomotion::System::RosClockFactory>(argc, argv));

   // Add a sleep
   BipedalLocomotion::clock().sleepFor(2000ms);

   auto start = BipedalLocomotion::clock().now();
   foo();
   auto end = BipedalLocomotion::clock().now();
   std::chrono::duration<double, std::milli> elapsed = end - start;

   return 0;
}

Base classes

class IClock
IClock is the interface to the clock.

Public functions

auto now() -> std::chrono::nanoseconds final
Get ROS current time.
void sleepFor(const std::chrono::nanoseconds& sleepDuration) final
Blocks the execution of the current thread for at least the specified sleepDuration.
void sleepUntil(const std::chrono::nanoseconds& sleepTime) final
Blocks the execution of the current thread until specified sleepTime has been reached.
void yield() final
Provides a hint to the implementation to reschedule the execution of threads, allowing other threads to run.

Function documentation

std::chrono::nanoseconds BipedalLocomotion::System::RosClock::now() final

Get ROS current time.

Returns the current time computed from rclcpp::Clock::now()