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::PhysicallyStableClock Class Reference

#include <PhysicallyStableClock.h>

Inherits ROS2::SimulationClock.

Public Member Functions

void Activate () override
 
void Deactivate () override
 
builtin_interfaces::msg::Time GetROSTimestamp () const override
 
- Public Member Functions inherited from ROS2::SimulationClock
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 changes source to physics of timestamps that are provided by GetROSTimestamp. The simulated clock is incremented with delta times that were simulated by physics. Clock register and observes AZ::PhysicsScene and when simulation starts, it attaches and starts to count updates. It is recommended to use with high-frequency sensors such as odometry and IMUs.

Member Function Documentation

◆ Activate()

void ROS2::PhysicallyStableClock::Activate ( )
overridevirtual

Reimplemented from ROS2::SimulationClock.

◆ Deactivate()

void ROS2::PhysicallyStableClock::Deactivate ( )
overridevirtual

Reimplemented from ROS2::SimulationClock.

◆ GetROSTimestamp()

builtin_interfaces::msg::Time ROS2::PhysicallyStableClock::GetROSTimestamp ( ) const
overridevirtual

Get simulation time as ROS2 message.

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

Reimplemented from ROS2::SimulationClock.


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