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

added HomePosition msg and some blueprint sub/pub #172

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
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
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,7 @@ geometry_msgs/TwistWithCovariance | ✓ | ✓
geometry_msgs/Vector3 | ✓ | ✓
grid_map_msgs/GridMap | ✓ | ✓
grid_map_msgs/GridMapInfo | ✓ | ✓
mavros_msgs/HomePosition | ✓ | ✓
nav_msgs/Odometry | ✓ | ✓
nav_msgs/Path | ✓ | ✓
rosgraph_msgs/Clock | ✓ | ✓
Expand Down
22 changes: 22 additions & 0 deletions Source/ROSIntegration/Classes/RI/Topic.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ enum class EMessageType : uint8
{
String = 0,
Float32 = 1,
PoseStamped = 2,
TwistStamped = 3,
Twist = 4,
HomePosition = 5
};

UCLASS(Blueprintable)
Expand Down Expand Up @@ -62,6 +66,18 @@ class ROSINTEGRATION_API UTopic: public UObject
UFUNCTION(BlueprintImplementableEvent, Category = ROS)
void OnFloat32Message(const float& Data);

UFUNCTION(BlueprintImplementableEvent, Category = ROS)
void OnPoseStampedMessage(const FVector& Position, const FRotator& Rotation);

UFUNCTION(BlueprintImplementableEvent, Category = ROS)
void OnTwistStampedMessage(const FVector& Linear, const FVector& Angular);

UFUNCTION(BlueprintImplementableEvent, Category = ROS)
void OnTwistMessage(const FVector& Linear, const FVector& Angular);

UFUNCTION(BlueprintImplementableEvent, Category = ROS)
void OnHomePositionMessage(const FVector& Geo, const FVector& Position, const FRotator& Orientation, const FVector& Approach);

UPROPERTY()
UROSIntegrationCore* _ROSIntegrationCore = nullptr;

Expand Down Expand Up @@ -89,6 +105,12 @@ class ROSINTEGRATION_API UTopic: public UObject
UFUNCTION(BlueprintCallable, Category = "ROS|Topic")
bool PublishStringMessage(const FString& Message);

UFUNCTION(BlueprintCallable, Category = "ROS|Topic")
bool PublishTwistStampedMessage(const FVector& Linear, const FVector& Angular);

UFUNCTION(BlueprintCallable, Category = "ROS|Topic")
bool PublishTwistMessage(const FVector& Linear, const FVector& Angular);

// Helper to keep track of self-destruction for async functions
TSharedPtr<UTopic, ESPMode::ThreadSafe> _SelfPtr;

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#include "Conversion/Messages/geographic_msgs/GeographicMsgsGeoPointConverter.h"

#include "geographic_msgs/GeoPoint.h"

UGeographicMsgsGeoPointConverter::UGeographicMsgsGeoPointConverter()
{
_MessageType = "geographic_msgs/GeoPoint";
}

bool UGeographicMsgsGeoPointConverter::ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg)
{
auto msg = new ROSMessages::geographic_msgs::GeoPoint();
BaseMsg = TSharedPtr<FROSBaseMsg>(msg);
return _bson_extract_child_geo_point(message->full_msg_bson_, "msg", msg);
}

bool UGeographicMsgsGeoPointConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message)
{
auto CastMSG = StaticCastSharedPtr<ROSMessages::geographic_msgs::GeoPoint>(BaseMsg);
*message = bson_new();
_bson_append_geo_point(*message, CastMSG.Get());

return true;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#include "Conversion/Messages/geographic_msgs/GeographicMsgsGeoPointConverter.h"

#include "geographic_msgs/GeoPoint.h"

UGeographicMsgsGeoPointConverter::UGeographicMsgsGeoPointConverter()
{
_MessageType = "geographic_msgs/GeoPoint";
}

bool UGeographicMsgsGeoPointConverter::ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg)
{
auto msg = new ROSMessages::geographic_msgs::GeoPoint();
BaseMsg = TSharedPtr<FROSBaseMsg>(msg);
return _bson_extract_child_geo_point(message->full_msg_bson_, "msg", msg);
}

bool UGeographicMsgsGeoPointConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message)
{
auto CastMSG = StaticCastSharedPtr<ROSMessages::geographic_msgs::GeoPoint>(BaseMsg);

*message = bson_new();
bson_init(*message);
_bson_append_geo_point(*message, CastMSG.Get());

return true;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
#pragma once

#include <CoreMinimal.h>
#include "Conversion/Messages/BaseMessageConverter.h"
#include "geographic_msgs/GeoPoint.h"
#include "Conversion/Messages/std_msgs/StdMsgsFloat32Converter.h"
#include "GeographicMsgsGeoPointConverter.generated.h"


UCLASS()
class ROSINTEGRATION_API UGeographicMsgsGeoPointConverter : public UBaseMessageConverter
{
GENERATED_BODY()

public:
UGeographicMsgsGeoPointConverter();
virtual bool ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg);
virtual bool ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message);

static bool _bson_extract_child_geo_point(bson_t *b, FString key, ROSMessages::geographic_msgs::GeoPoint * msg, bool LogOnErrors = true)
{
bool KeyFound = true;

msg->latitude = GetDoubleFromBSON(key + ".latitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
msg->longitude = GetDoubleFromBSON(key + ".longitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
msg->altitude = GetDoubleFromBSON(key + ".altitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
return true;
}

static void _bson_append_child_geo_point(bson_t *b, const char *key, const ROSMessages::geographic_msgs::GeoPoint * msg)
{
bson_t child;
BSON_APPEND_DOCUMENT_BEGIN(b, key, &child);
_bson_append_geo_point(&child, msg);
bson_append_document_end(b, &child);
}

static void _bson_append_geo_point(bson_t *b, const ROSMessages::geographic_msgs::GeoPoint * msg)
{
BSON_APPEND_DOUBLE(b, "latitude", msg->latitude);
BSON_APPEND_DOUBLE(b, "longitude", msg->longitude);
BSON_APPEND_DOUBLE(b, "altitude", msg->altitude);
}
};
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
#pragma once

#include <CoreMinimal.h>
#include "Conversion/Messages/BaseMessageConverter.h"
#include "geographic_msgs/GeoPoint.h"
#include "Conversion/Messages/std_msgs/StdMsgsFloat32Converter.h"
#include "GeographicMsgsGeoPointConverter.generated.h"


UCLASS()
class ROSINTEGRATION_API UGeographicMsgsGeoPointConverter : public UBaseMessageConverter
{
GENERATED_BODY()

public:
UGeographicMsgsGeoPointConverter();
virtual bool ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg);
virtual bool ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message);

static bool _bson_extract_child_geo_point(bson_t *b, FString key, ROSMessages::geographic_msgs::GeoPoint * msg, bool LogOnErrors = true)
{
bool KeyFound = true;

msg->latitude = GetDoubleFromBSON(key + ".latitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
msg->longitude = GetDoubleFromBSON(key + ".longitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
msg->altitude = GetDoubleFromBSON(key + ".altitude", b, KeyFound, LogOnErrors); if (!KeyFound) return false;
return true;
}

static void _bson_append_child_geo_point(bson_t *b, const char *key, const ROSMessages::geographic_msgs::GeoPoint * msg)
{
bson_t child;
BSON_APPEND_DOCUMENT_BEGIN(b, key, &child);
_bson_append_geo_point(&child, ps);
bson_append_document_end(b, &child);
}

static void _bson_append_geo_point(bson_t *b, const ROSMessages::geographic_msgs::GeoPoint * ps)
{
BSON_APPEND_DOUBLE(b, "latitude", ps->latitude);
BSON_APPEND_DOUBLE(b, "longitude", ps->longitude);
BSON_APPEND_DOUBLE(b, "altitude", ps->altitude);
}
};
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "Conversion/Messages/mavros_msgs/MavrosMsgsHomePositionConverter.h"


UMavrosMsgsHomePositionConverter::UMavrosMsgsHomePositionConverter()
{
_MessageType = "mavros_msgs/HomePosition";
}

bool UMavrosMsgsHomePositionConverter::ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg)
{
auto msg = new ROSMessages::mavros_msgs::HomePosition();
BaseMsg = TSharedPtr<FROSBaseMsg>(msg);

if (!UStdMsgsHeaderConverter::_bson_extract_child_header(message->full_msg_bson_, TEXT("msg.header"), &msg->header)) return false;
if (!UGeometryMsgsPointConverter::_bson_extract_child_point(message->full_msg_bson_, TEXT("msg.position"), &msg->position)) return false;
if (!UGeometryMsgsQuaternionConverter::_bson_extract_child_quaternion(message->full_msg_bson_, TEXT("msg.orientation"), &msg->orientation)) return false;
if (!UGeometryMsgsVector3Converter::_bson_extract_child_vector3(message->full_msg_bson_, TEXT("msg.approach"), &msg->approach)) return false;
if (!UGeographicMsgsGeoPointConverter::_bson_extract_child_geo_point(message->full_msg_bson_, TEXT("msg.geo"), &msg->geo)) return false;

return true;
}

bool UMavrosMsgsHomePositionConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message)
{
auto CastMSG = StaticCastSharedPtr<ROSMessages::mavros_msgs::HomePosition>(BaseMsg);
*message = bson_new();
_bson_append_home_position(*message, CastMSG.Get());

return true;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "Conversion/Messages/mavros_msgs/MavrosMsgsHomePositionConverter.h"


UMavrosMsgsHomePositionConverter::UMavrosMsgsHomePositionConverter()
{
_MessageType = "mavros_msgs/HomePosition";
}

bool UMavrosMsgsHomePositionConverter::ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg)
{
auto msg = new ROSMessages::mavros_msgs::HomePosition();
BaseMsg = TSharedPtr<FROSBaseMsg>(msg);

if (!UStdMsgsHeaderConverter::_bson_extract_child_header(message->full_msg_bson_, TEXT("msg.header"), &msg->header)) return false;
if (!UGeometryMsgsPointConverter::_bson_extract_child_point(message->full_msg_bson_, TEXT("msg.position"), &msg->position)) return false;
if (!UGeometryMsgsQuaternionConverter::_bson_extract_child_quaternion(message->full_msg_bson_, TEXT("msg.orientation"), &msg->orientation)) return false;
if (!UGeometryMsgsVector3Converter::_bson_extract_child_vector3(message->full_msg_bson_, TEXT("msg.approach"), &msg->approach)) return false;
if (!UGeographicMsgsGeoPointConverter::_bson_extract_child_geo_point(message->full_msg_bson_, TEXT("msg.geo"), &msg->geo)) return false;

return true;
}

bool UMavrosMsgsHomePositionConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message)
{
auto CastMSG = StaticCastSharedPtr<ROSMessages::mavros_msgs::HomePosition>(BaseMsg);
*message = bson_new();
_bson_append_home_position(*message, CastMSG.Get());

return true;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
#pragma once

#include <CoreMinimal.h>
#include "Conversion/Messages/BaseMessageConverter.h"
#include "mavros_msgs/HomePosition.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Point.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/Vector3.h"
#include "geographic_msgs/GeoPoint.h"
#include "Conversion/Messages/std_msgs/StdMsgsHeaderConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsPointConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsQuaternionConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsVector3Converter.h"
#include "Conversion/Messages/geographic_msgs/GeographicMsgsGeoPointConverter.h"
#include "MavrosMsgsHomePositionConverter.generated.h"


UCLASS()
class ROSINTEGRATION_API UMavrosMsgsHomePositionConverter : public UBaseMessageConverter
{
GENERATED_BODY()

public:
UMavrosMsgsHomePositionConverter();
virtual bool ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg);
virtual bool ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message);

static bool _bson_extract_child_home_position(bson_t *b, FString key, ROSMessages::mavros_msgs::HomePosition* msg, bool LogOnErrors = true)
{
bool KeyFound = true;

KeyFound &= UStdMsgsHeaderConverter::_bson_extract_child_header(b, key + ".header", &msg->header);
KeyFound &= UGeometryMsgsPointConverter::_bson_extract_child_point(b, key + ".position", &msg->position);
KeyFound &= UGeometryMsgsQuaternionConverter::_bson_extract_child_quaternion(b, key + ".orientation", &msg->orientation);
KeyFound &= UGeometryMsgsVector3Converter::_bson_extract_child_vector3(b, key + ".approach", &msg->approach);
KeyFound &= UGeographicMsgsGeoPointConverter::_bson_extract_child_geo_point(b, key + ".geo", &msg->geo);

return KeyFound;
}

static void _bson_append_child_home_position(bson_t *b, const char *key, const ROSMessages::mavros_msgs::HomePosition* msg)
{
bson_t child;
BSON_APPEND_DOCUMENT_BEGIN(b, key, &child);
_bson_append_home_position(&child, msg);
bson_append_document_end(b, &child);
}

static void _bson_append_home_position(bson_t *b, const ROSMessages::mavros_msgs::HomePosition* msg)
{
UStdMsgsHeaderConverter::_bson_append_header(b, &(msg->header));
UGeometryMsgsPointConverter::_bson_append_child_point(b, "position", &(msg->position));
UGeometryMsgsQuaternionConverter::_bson_append_child_quaternion(b, "orientation", &(msg->orientation));
UGeometryMsgsVector3Converter::_bson_append_child_vector3(b, "approach", &(msg->approach));
UGeographicMsgsGeoPointConverter::_bson_append_child_geo_point(b, "geo", &(msg->geo));
}
};
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
#pragma once

#include <CoreMinimal.h>
#include "Conversion/Messages/BaseMessageConverter.h"
#include "mavros_msgs/HomePosition.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Point.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/Vector3.h"
#include "geographic_msgs/GeoPoint.h"
#include "Conversion/Messages/std_msgs/StdMsgsHeaderConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsPointConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsQuaternionConverter.h"
#include "Conversion/Messages/geometry_msgs/GeometryMsgsVector3Converter.h"
#include "Conversion/Messages/geographic_msgs/GeographicMsgsGeoPointConverter.h"
#include "MavrosMsgsHomePositionConverter.generated.h"


UCLASS()
class ROSINTEGRATION_API UMavrosMsgsHomePositionConverter : public UBaseMessageConverter
{
GENERATED_BODY()

public:
UMavrosMsgsHomePositionConverter();
virtual bool ConvertIncomingMessage(const ROSBridgePublishMsg* message, TSharedPtr<FROSBaseMsg> &BaseMsg);
virtual bool ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message);

static bool _bson_extract_child_home_position(bson_t *b, FString key, ROSMessages::mavros_msgs::HomePosition* msg, bool LogOnErrors = true)
{
bool KeyFound = true;

KeyFound &= UStdMsgsHeaderConverter::_bson_extract_child_header(b, key + ".header", &msg->header);
KeyFound &= UGeometryMsgsPointConverter::_bson_extract_child_point(b, key + ".position", &msg->position);
KeyFound &= UGeometryMsgsQuaternionConverter::_bson_extract_child_quaternion(b, key + ".orientation", &msg->orientation);
KeyFound &= UGeometryMsgsVector3Converter::_bson_extract_child_vector3(b, key + ".approach", &msg->approach);
KeyFound &= UGeographicMsgsGeoPointConverter::_bson_extract_child_geo_point(b, key + ".geo", &msg->geo);

return KeyFound;
}

static void _bson_append_child_home_position(bson_t *b, const char *key, const ROSMessages::mavros_msgs::HomePosition* ps)
{
bson_t layout;
BSON_APPEND_DOCUMENT_BEGIN(b, key, &layout);
_bson_append_home_position(&layout, ps);
bson_append_document_end(b, &layout);
}

static void _bson_append_home_position(bson_t *b, const ROSMessages::mavros_msgs::HomePosition* ps)
{
UStdMsgsHeaderConverter::_bson_append_header(b, &(ps->header));
UGeometryMsgsPointConverter::_bson_append_child_point(b, "position", &(ps->position));
UGeometryMsgsQuaternionConverter::_bson_append_child_quaternion(b, "orientation", &(ps->orientation));
UGeometryMsgsVector3Converter::_bson_append_child_vector3(b, "approach", &(ps->approach));
UGeographicMsgsGeoPointConverter::_bson_append_child_geo_point(b, "geo", &(ps->geo));
}
};
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#pragma once

#include "CoreMinimal.h"
#include <CoreMinimal.h>
#include "Conversion/Messages/BaseMessageConverter.h"
#include "std_msgs/Bool.h"
#include "StdMsgsBoolConverter.generated.h"
Expand Down
Loading