Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
43 changes: 43 additions & 0 deletions Source/rclUE/Private/Msgs/ROSNotification.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#include "Msgs/ROSNotification2D.h"

void UROSNotification2DMsg::Init()
{
guided_vr_interfaces__msg__Notification2D__init(&Notification2D_msg);
}

void UROSNotification2DMsg::Fini()
{
guided_vr_interfaces__msg__Notification2D__fini(&Notification2D_msg);
}

const rosidl_message_type_support_t* UROSNotification2DMsg::GetTypeSupport() const
{
return ROSIDL_GET_MSG_TYPE_SUPPORT(guided_vr_interfaces, msg, Notification2D);
}

void UROSNotification2DMsg::SetMsg(const FROSNotification2D& Input)
{
Input.SetROS2(Notification2D_msg);
}

void UROSNotification2DMsg::GetMsg(FROSNotification2D& Output) const
{
Output.SetFromROS2(Notification2D_msg);
}

void* UROSNotification2DMsg::Get()
{
return &Notification2D_msg;
}

FString UROSNotification2DMsg::MsgToString() const
{
// Provide a readable summary
return FString::Printf(
TEXT("Notification2D(Source=%s, Level=%d, Id=%d, PolygonPoints=%d)"),
*FString(Notification2D_msg.source.data.data),
Notification2D_msg.level.data,
Notification2D_msg.id,
static_cast<int32>(Notification2D_msg.polygon.size)
);
}
90 changes: 90 additions & 0 deletions Source/rclUE/Public/Msgs/ROSNotification2D.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
#pragma once

#include "CoreMinimal.h"
#include "guided_vr_interfaces/msg/notification2_d.h"
#include "Msgs/ROS2GenericMsg.h"
#include "geometry_msgs/msg/point.h"
#include "rclcUtilities.h"
#include "ROS2Time.h"
#include "ROSNotification2D.generated.h"

USTRUCT(BlueprintType)
struct RCLUE_API FROSNotification2D
{
GENERATED_BODY()

UPROPERTY(EditAnywhere, BlueprintReadWrite)
FString Source;

UPROPERTY(EditAnywhere, BlueprintReadWrite)
FString Desc;

UPROPERTY(EditAnywhere, BlueprintReadWrite)
uint8 Level;

UPROPERTY(EditAnywhere, BlueprintReadWrite)
FROSTime Stamp; // Assume you have a Blueprintable wrapper for builtin_interfaces/Time

UPROPERTY(EditAnywhere, BlueprintReadWrite)
int32 Id;

UPROPERTY(EditAnywhere, BlueprintReadWrite)
TArray<FVector2D> Polygon;

void SetROS2(guided_vr_interfaces__msg__Notification2D& OutROSData) const
{
UROS2Utils::StringUEToROS(Source, OutROSData.source.data);
UROS2Utils::StringUEToROS(Source, OutROSData.desc.data);
OutROSData.level.data = Level;
Stamp.SetROS2(OutROSData.stamp);
OutROSData.id = Id;
// Convert Polygon array
size_t sz = Polygon.Num();
if (OutROSData.polygon.size != sz) {
geometry_msgs__msg__Point__Sequence__fini(&OutROSData.polygon);
geometry_msgs__msg__Point__Sequence__init(&OutROSData.polygon, sz);
}
for (size_t i = 0; i < sz; ++i) {
OutROSData.polygon.data[i].x = Polygon[i].X;
OutROSData.polygon.data[i].y = Polygon[i].Y;
OutROSData.polygon.data[i].z = 0.0;
}
}

void SetFromROS2(const guided_vr_interfaces__msg__Notification2D& InROSData)
{
Source = UROS2Utils::StringROSToUE<rosidl_runtime_c__String>(InROSData.source.data);
Desc = UROS2Utils::StringROSToUE<rosidl_runtime_c__String>(InROSData.desc.data);
Level = InROSData.level.data;
Stamp.SetFromROS2(InROSData.stamp);
Id = InROSData.id;
Polygon.Empty();
for (size_t i = 0; i < InROSData.polygon.size; ++i) {
auto& pt = InROSData.polygon.data[i];
Polygon.Add(FVector2D(pt.x, pt.y));
}
}
};

UCLASS()
class RCLUE_API UROSNotification2DMsg : public UROS2GenericMsg
{
GENERATED_BODY()

public:
virtual void Init() override;
virtual void Fini() override;
virtual const rosidl_message_type_support_t* GetTypeSupport() const override;

UFUNCTION(BlueprintCallable)
void SetMsg(const FROSNotification2D& Input);

UFUNCTION(BlueprintCallable)
void GetMsg(FROSNotification2D& Output) const;

virtual void* Get() override;
virtual FString MsgToString() const override;

private:
guided_vr_interfaces__msg__Notification2D Notification2D_msg;
};
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
// generated from rosidl_generator_cpp/resource/idl__builder.hpp.em
// with input from guided_vr_interfaces:msg/Notification2D.idl
// generated code does not contain a copyright notice

#ifndef GUIDED_VR_INTERFACES__MSG__DETAIL__NOTIFICATION2_D__BUILDER_HPP_
#define GUIDED_VR_INTERFACES__MSG__DETAIL__NOTIFICATION2_D__BUILDER_HPP_

#include <algorithm>
#include <utility>

#include "guided_vr_interfaces/msg/detail/notification2_d__struct.hpp"
#include "rosidl_runtime_cpp/message_initialization.hpp"


namespace guided_vr_interfaces
{

namespace msg
{

namespace builder
{

class Init_Notification2D_polygon
{
public:
explicit Init_Notification2D_polygon(::guided_vr_interfaces::msg::Notification2D & msg)
: msg_(msg)
{}
::guided_vr_interfaces::msg::Notification2D polygon(::guided_vr_interfaces::msg::Notification2D::_polygon_type arg)
{
msg_.polygon = std::move(arg);
return std::move(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

class Init_Notification2D_id
{
public:
explicit Init_Notification2D_id(::guided_vr_interfaces::msg::Notification2D & msg)
: msg_(msg)
{}
Init_Notification2D_polygon id(::guided_vr_interfaces::msg::Notification2D::_id_type arg)
{
msg_.id = std::move(arg);
return Init_Notification2D_polygon(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

class Init_Notification2D_stamp
{
public:
explicit Init_Notification2D_stamp(::guided_vr_interfaces::msg::Notification2D & msg)
: msg_(msg)
{}
Init_Notification2D_id stamp(::guided_vr_interfaces::msg::Notification2D::_stamp_type arg)
{
msg_.stamp = std::move(arg);
return Init_Notification2D_id(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

class Init_Notification2D_level
{
public:
explicit Init_Notification2D_level(::guided_vr_interfaces::msg::Notification2D & msg)
: msg_(msg)
{}
Init_Notification2D_stamp level(::guided_vr_interfaces::msg::Notification2D::_level_type arg)
{
msg_.level = std::move(arg);
return Init_Notification2D_stamp(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

class Init_Notification2D_desc
{
public:
explicit Init_Notification2D_desc(::guided_vr_interfaces::msg::Notification2D & msg)
: msg_(msg)
{}
Init_Notification2D_level desc(::guided_vr_interfaces::msg::Notification2D::_desc_type arg)
{
msg_.desc = std::move(arg);
return Init_Notification2D_level(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

class Init_Notification2D_source
{
public:
Init_Notification2D_source()
: msg_(::rosidl_runtime_cpp::MessageInitialization::SKIP)
{}
Init_Notification2D_desc source(::guided_vr_interfaces::msg::Notification2D::_source_type arg)
{
msg_.source = std::move(arg);
return Init_Notification2D_desc(msg_);
}

private:
::guided_vr_interfaces::msg::Notification2D msg_;
};

} // namespace builder

} // namespace msg

template<typename MessageType>
auto build();

template<>
inline
auto build<::guided_vr_interfaces::msg::Notification2D>()
{
return guided_vr_interfaces::msg::builder::Init_Notification2D_source();
}

} // namespace guided_vr_interfaces

#endif // GUIDED_VR_INTERFACES__MSG__DETAIL__NOTIFICATION2_D__BUILDER_HPP_
Loading