Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use ROS 2 clock for sensor triggering #807

Open
wants to merge 3 commits into
base: development
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion Gems/ROS2/Code/Include/ROS2/Clock/ROS2Clock.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ namespace ROS2
//! the /use_sim_time parameter set to true.
class ROS2Clock
{
static constexpr size_t FramesNumberForStats = 60;

public:
ROS2Clock();
Expand Down
3 changes: 3 additions & 0 deletions Gems/ROS2/Code/Include/ROS2/ROS2Bus.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,9 @@ namespace ROS2
//! Obtains a simulation clock that is used across simulation.
//! @returns constant reference to currently running clock.
virtual const ROS2Clock& GetSimulationClock() const = 0;

//! Returns an expected loop time of simulation. It is an estimation from past frames.
virtual float GetExpectedSimulationLoopTime() const = 0;
};

class ROS2BusTraits : public AZ::EBusTraits
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,6 @@ namespace ROS2
{
return false;
}

const float sourceFrequencyEstimation = 1.0f / sourceDeltaTime;
const float numberOfFrames =
m_adaptedFrequency <= sourceFrequencyEstimation ? (sourceFrequencyEstimation / m_adaptedFrequency) : 1.0f;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <AzCore/EBus/OrderedEvent.h>
#include <AzFramework/Physics/Common/PhysicsEvents.h>
#include <AzFramework/Physics/Common/PhysicsTypes.h>
#include <ROS2/ROS2Bus.h>
#include <ROS2/Sensor/Events/SensorEventSource.h>

namespace ROS2
Expand All @@ -32,5 +33,6 @@ namespace ROS2

private:
AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_onSceneSimulationEventHandler; ///< Handler for physics callback.
builtin_interfaces::msg::Time m_lastSimulationTime; ///< Last simulation time.
};
} // namespace ROS2
10 changes: 7 additions & 3 deletions Gems/ROS2/Code/Include/ROS2/Sensor/Events/TickBasedSource.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,14 @@
#include <AzCore/Component/TickBus.h>
#include <AzCore/EBus/Event.h>
#include <ROS2/Sensor/Events/SensorEventSource.h>

#include <ROS2/ROS2Bus.h>
namespace ROS2
{
//! Class implementing system TickBus (draw calls) as sensor event source. Source event (ROS2::SensorEventSource) is signalled based on
//! system ticks.
//! @see ROS2::SensorEventSource
class TickBasedSource final
: public SensorEventSource<AZ::Event, AZ::EventHandler, float, AZ::ScriptTimePoint>
: public SensorEventSource<AZ::Event, AZ::EventHandler, float>
, protected AZ::TickBus::Handler
{
public:
Expand All @@ -28,10 +28,14 @@ namespace ROS2
// Overrides of ROS2::SensorEventSource.
void Start() override;
void Stop() override;
[[nodiscard]] float GetDeltaTime(float deltaTime, AZ::ScriptTimePoint time) const override;
[[nodiscard]] float GetDeltaTime(float deltaTime) const override;

private:
// Override of AZ::TickBus::Handler.
void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;

builtin_interfaces::msg::Time m_lastTickTimestamp;
AZStd::deque<float> m_deltaTimes;
constexpr static size_t m_maxDeltaTimes = 100;
};
} // namespace ROS2
13 changes: 11 additions & 2 deletions Gems/ROS2/Code/Source/Sensor/Events/PhysicsBasedSource.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
*/

#include <AzFramework/Physics/PhysicsSystem.h>

#include <ROS2/Utilities/ROS2Conversions.h>
#include <ROS2/Sensor/Events/PhysicsBasedSource.h>
#include <ROS2/Sensor/SensorConfiguration.h>

Expand All @@ -23,10 +25,17 @@ namespace ROS2
void PhysicsBasedSource::Start()
{
m_onSceneSimulationEventHandler.Disconnect();
const auto *ros2Interface = ROS2Interface::Get();
michalpelka marked this conversation as resolved.
Show resolved Hide resolved
AZ_Assert(ros2Interface, "ROS2 interface is not initialized.");

m_onSceneSimulationEventHandler = AzPhysics::SceneEvents::OnSceneSimulationFinishHandler(
[this](AzPhysics::SceneHandle sceneHandle, float deltaTime)
[this, ros2Interface](AzPhysics::SceneHandle sceneHandle, float deltaTime)
{
m_sourceEvent.Signal(sceneHandle, deltaTime);
const auto simulationTime = ros2Interface->GetROSTimestamp();

float deltaSimTime = ROS2Conversions::GetTimeDifference(m_lastSimulationTime, simulationTime);
michalpelka marked this conversation as resolved.
Show resolved Hide resolved
m_sourceEvent.Signal(sceneHandle, deltaSimTime);
m_lastSimulationTime = simulationTime;
});

auto* sceneInterface = AZ::Interface<AzPhysics::SceneInterface>::Get();
Expand Down
12 changes: 9 additions & 3 deletions Gems/ROS2/Code/Source/Sensor/Events/TickBasedSource.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,9 @@

#include <ROS2/Sensor/Events/TickBasedSource.h>
#include <ROS2/Sensor/SensorConfiguration.h>

#include <ROS2/ROS2Bus.h>
#include <ROS2/Utilities/ROS2Conversions.h>
#include <AzCore/std/numeric.h>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this header needed?

namespace ROS2
{
void TickBasedSource::Reflect(AZ::ReflectContext* context)
Expand All @@ -29,13 +31,17 @@ namespace ROS2
AZ::TickBus::Handler::BusDisconnect();
}

float TickBasedSource::GetDeltaTime(float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time) const
float TickBasedSource::GetDeltaTime(float deltaTime) const
{
return deltaTime;
}

void TickBasedSource::OnTick(float deltaTime, AZ::ScriptTimePoint time)
{
m_sourceEvent.Signal(deltaTime, time);
AZ_UNUSED(time);
AZ_UNUSED(deltaTime);
auto simTimestamp = ROS2Interface::Get()->GetExpectedSimulationLoopTime();
michalpelka marked this conversation as resolved.
Show resolved Hide resolved
m_sourceEvent.Signal(simTimestamp);

}
} // namespace ROS2
24 changes: 23 additions & 1 deletion Gems/ROS2/Code/Source/SystemComponents/ROS2SystemComponent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,14 @@
#include <AzCore/std/string/string_view.h>
#include <AzFramework/API/ApplicationAPI.h>
#include <ROS2/Sensor/SensorConfigurationRequestBus.h>

#include <ROS2/Utilities/ROS2Conversions.h>
#include <AzCore/std/numeric.h>
#include <AzCore/std/sort.h>
namespace ROS2
{
constexpr AZStd::string_view ClockTypeConfigurationKey = "/O3DE/ROS2/ClockType";
constexpr AZStd::string_view PublishClockConfigurationKey = "/O3DE/ROS2/PublishClock";
constexpr size_t FramesNumberForStats = 60;

void ROS2SystemComponent::Reflect(AZ::ReflectContext* context)
{
Expand Down Expand Up @@ -230,6 +233,25 @@ namespace ROS2
m_simulationClock->Tick();
m_executor->spin_some();
}
// Calculate simulation loop time
const auto simTimestamp = m_simulationClock->GetROSTimestamp();
float deltaSimTime = ROS2Conversions::GetTimeDifference(m_lastSimulationTime, simTimestamp);
michalpelka marked this conversation as resolved.
Show resolved Hide resolved

// Filter out the outliers
m_simulationLoopTimes.push_back(deltaSimTime);
if (m_simulationLoopTimes.size() > FramesNumberForStats)
{
m_simulationLoopTimes.pop_front();
}
AZStd::vector<float> frameTimeSorted{ m_simulationLoopTimes.begin(), m_simulationLoopTimes.end() };
AZStd::sort(frameTimeSorted.begin(), frameTimeSorted.end());
m_currentMedian = frameTimeSorted[frameTimeSorted.size() / 2];

m_lastSimulationTime = simTimestamp;
}

float ROS2SystemComponent::GetExpectedSimulationLoopTime() const
{
return m_currentMedian;
}
} // namespace ROS2
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ namespace ROS2
builtin_interfaces::msg::Time GetROSTimestamp() const override;
void BroadcastTransform(const geometry_msgs::msg::TransformStamped& t, bool isDynamic) override;
const ROS2Clock& GetSimulationClock() const override;
float GetExpectedSimulationLoopTime() const override;
//////////////////////////////////////////////////////////////////////////

protected:
Expand All @@ -89,5 +90,9 @@ namespace ROS2
AZStd::unique_ptr<tf2_ros::StaticTransformBroadcaster> m_staticTFBroadcaster;
AZStd::unique_ptr<ROS2Clock> m_simulationClock;
NodeChangedEvent m_nodeChangedEvent;

AZStd::deque<float> m_simulationLoopTimes;
builtin_interfaces::msg::Time m_lastSimulationTime;
float m_currentMedian = 1.f/60.0f;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
float m_currentMedian = 1.f/60.0f;
float m_currentMedian = 1.0f / 60.0f;

Btw. I would also rename the variable (ROS2SystemComponent->currentMedian?), maybe m_simTimeMedian?

};
} // namespace ROS2