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

Spline subscriber offset improvements #91

Merged
merged 2 commits into from
Nov 28, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
45 changes: 44 additions & 1 deletion Gems/RobotecSplineTools/Code/Source/Clients/SplineSubscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <AzCore/Component/TransformBus.h>
#include <AzCore/Serialization/EditContext.h>
#include <AzCore/Serialization/SerializeContext.h>
#include <LmbrCentral/Scripting/TagComponentBus.h>
#include <LmbrCentral/Shape/SplineComponentBus.h>
#include <ROS2/Georeference/GeoreferenceBus.h>

Expand Down Expand Up @@ -54,6 +55,32 @@ namespace SplineTools
});
}

bool SplineSubscriber::GetOffsetTransform(AZ::Transform& transform)
michalpelka marked this conversation as resolved.
Show resolved Hide resolved
{
AZ::EBusAggregateResults<AZ::EntityId> aggregator;
const LmbrCentral::Tag tag = AZ::Crc32(m_config.m_startOffsetTag);
LmbrCentral::TagGlobalRequestBus::EventResult(aggregator, tag, &LmbrCentral::TagGlobalRequests::RequestTaggedEntities);

AZ_Warning(
"SplineSubscriber",
aggregator.values.size() <= 1,
"Multiple entities found with tag %s. The first entity will be used.",
m_config.m_startOffsetTag.c_str());

AZ_Warning("SplineSubscriber", !aggregator.values.empty(), "No entity with tag found %s.", m_config.m_startOffsetTag.c_str());

if (!aggregator.values.empty())
{
AZ::Transform offsetTransform = AZ::Transform::CreateIdentity();
const AZ::EntityId& entityId = aggregator.values[0];
AZ::TransformBus::EventResult(offsetTransform, entityId, &AZ::TransformBus::Events::GetWorldTM);
transform = offsetTransform;
return true;
}

return false;
}

void SplineSubscriber::OnSplineReceived(const nav_msgs::msg::Path& msg)
{
AZ::SplinePtr splinePtr;
Expand All @@ -64,6 +91,10 @@ namespace SplineTools
AZ::Transform worldTm = AZ::Transform::CreateIdentity();
AZ::TransformBus::EventResult(worldTm, GetEntityId(), &AZ::TransformBus::Events::GetWorldTM);
worldTm.Invert();

AZ::Transform offsetTransform = AZ::Transform::CreateIdentity();
auto hasOffset = GetOffsetTransform(offsetTransform);

AZStd::string frame{ msg.header.frame_id.c_str(), msg.header.frame_id.size() };
AZStd::to_upper(frame.begin(), frame.end());
AZ_Printf("SplineSubscriber", "Frame: %s", frame.data());
Expand All @@ -76,7 +107,19 @@ namespace SplineTools

if (frame.empty())
{
points[i] = worldTm.TransformPoint(posePoint);
if (hasOffset)
{
auto referenceTranslation = offsetTransform.TransformPoint(posePoint);
points[i] = worldTm.TransformPoint(referenceTranslation);
}
else
{
points[i] = worldTm.TransformPoint(posePoint);
}
}
else if (frame == "LOCAL")
{
points[i] = posePoint;
}
else if (frame == "WGS84" && m_config.m_allowWGS84)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include "SplineSubscriberConfig.h"
#include <AzCore/Component/Component.h>
#include <AzCore/Math/Transform.h>
#include <ROS2/ROS2Bus.h>
#include <SplineTools/SplineToolsTypeIds.h>
#include <nav_msgs/msg/path.hpp>
Expand All @@ -20,6 +21,7 @@ namespace SplineTools
void Deactivate() override;

private:
bool GetOffsetTransform(AZ::Transform& transform);
void OnSplineReceived(const nav_msgs::msg::Path& msg);
SplineSubscriberConfiguration m_config;
rclcpp::Subscription<nav_msgs::msg::Path>::SharedPtr m_subscription;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ namespace SplineTools
->Version(0)
->Field("m_topicName", &SplineSubscriberConfiguration::m_topic)
->Field("m_allowWGS84", &SplineSubscriberConfiguration::m_allowWGS84)
->Field("m_resetOnActivation", &SplineSubscriberConfiguration::m_resetOnActivation);
->Field("m_resetOnActivation", &SplineSubscriberConfiguration::m_resetOnActivation)
->Field("m_startOffsetTag", &SplineSubscriberConfiguration::m_startOffsetTag);
if (auto editContext = serializeContext->GetEditContext())
{
editContext
Expand All @@ -32,7 +33,12 @@ namespace SplineTools
AZ::Edit::UIHandlers::Default,
&SplineSubscriberConfiguration::m_resetOnActivation,
"Reset On Activation",
"Reset On Activation");
"Reset On Activation")
->DataElement(
AZ::Edit::UIHandlers::Default,
&SplineSubscriberConfiguration::m_startOffsetTag,
"Start Offset Tag",
"Tag that will be used to set the start offset for the spline.");
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,5 +17,6 @@ namespace SplineTools
ROS2::TopicConfiguration m_topic{ rclcpp::ServicesQoS() };
bool m_allowWGS84{ true }; //! Allow WGS84 coordinates.
bool m_resetOnActivation{ true }; //! Reset entity's spline on activation.
AZStd::string m_startOffsetTag; //! Tag of the entity to use for the spline points offset.
};
} // namespace SplineTools