Open 3D Engine ROS2 Gem API Reference 23.10.0
O3DE is an open-source, fully-featured, high-fidelity, modular 3D engine for building games and simulations, available to every industry.
ROS2::SimulationClock Class Reference

Simulation clock which can tick and serve time stamps. More...

#include <SimulationClock.h>

Inherited by ROS2::PhysicallyStableClock.

Public Member Functions

virtual void Activate ()
 
virtual void Deactivate ()
 
virtual builtin_interfaces::msg::Time GetROSTimestamp () const
 
virtual void Tick ()
 
AZStd::chrono::duration< float, AZStd::chrono::seconds::period > GetExpectedSimulationLoopTime () const
 Returns an expected loop time of simulation. It is an estimation from past frames.
 

Detailed Description

Simulation clock which can tick and serve time stamps.

Member Function Documentation

◆ GetROSTimestamp()

virtual builtin_interfaces::msg::Time ROS2::SimulationClock::GetROSTimestamp ( ) const
virtual

Get simulation time as ROS2 message.

See also
ROS2Requests::GetROSTimestamp() for more details.

Reimplemented in ROS2::PhysicallyStableClock.

◆ Tick()

virtual void ROS2::SimulationClock::Tick ( )
virtual

Update time in the ROS 2 ecosystem. This will publish current time to the ROS 2 /clock topic.


The documentation for this class was generated from the following file: