Skip to content

Commit 8cc3475

Browse files
authored
Merge pull request #162 from tsender/master
Fixed memory leak when publishing messages
2 parents d903cc9 + dd01138 commit 8cc3475

File tree

44 files changed

+205
-103
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

44 files changed

+205
-103
lines changed

README.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,7 @@ Topic Message Type | ROS to UE4 | UE4 to ROS
187187
---------------------------------- | ---------- | ----------
188188
std_msgs/Header | ✓ | ✓
189189
std_msgs/String | ✓ | ✓
190+
std_msgs/Bool | ✓ | ✓
190191
std_msgs/Float32 | ✓ | ✓
191192
std_msgs/Float32MultiArray | ✓ | ✓
192193
std_msgs/MultiArrayDimension | ✓ | ✓
@@ -215,7 +216,7 @@ sensor_msgs/JointState | ✓ | ✓
215216
sensor_msgs/NavSatFix | ✓ | ✓
216217
sensor_msgs/NavSatStatus | ✓ | ✓
217218
sensor_msgs/PointCloud2 | ✓ | ✓
218-
sensor_msgs/RegionOfInterest | |
219+
sensor_msgs/RegionOfInterest | |
219220
sensor_msgs/LaserScan | ✓ | ✓
220221
actionlib_msgs/GoalID | ✓ | ✓
221222
actionlib_msgs/GoalStatus | ✓ | ✓
@@ -229,7 +230,7 @@ rospy_tutorials/AddTwoIntsResponse | ✓ | ✓
229230

230231
### Implementing New Message Types
231232

232-
To be able to send and receive message types with ROSIntegration we need two things: the message definition, as well as a converter of the data in that definition from and to BSON. For reference how to do that look into the message definitions in `Source\ROSIntegration\Public`, and the converters in `Source\ROSIntegration\Private\Conversion\Messages`.
233+
To be able to send and receive message types with ROSIntegration we need two things: the message definition, as well as a converter of the data in that definition from and to BSON. For reference how to do that look into the message definitions in `Source\ROSIntegration\Public`, and the converters in `Source\ROSIntegration\Private\Conversion\Messages`. To avoid any memory leaks, please follow the same steps as done in this repo when implementing your overriden `ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg> BaseMsg, bson_t** message)`. It is also recommended that you make your custom converters user-friendly by creating helper functions like `_bson_append_child_msg(...)` and `_bson_append_msg(...)` as you see in most of our message converter header files. If you do create such helper functions, follow our convention to avoid any memory leaks.
233234

234235
If you need one of the standard message types provided by ROS, you should implement them inside the ROSIntegration's folder structure. Please keep to the naming convention of the ROS documentation for the message definition.
235236
If you want to implement your own messages you can do that in your own project. You only need to add something like the following to the Build.cs-file of your project:

Source/ROSIntegration/Private/Conversion/Messages/actionlib_msgs/ActionlibMsgsGoalIDConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,7 @@ bool UActionlibMsgsGoalIDConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMs
1818
{
1919
auto GoalID = StaticCastSharedPtr<ROSMessages::actionlib_msgs::GoalID>(BaseMsg);
2020

21-
*message = new bson_t;
22-
bson_init(*message);
21+
*message = bson_new();
2322
_bson_append_goal_id(*message, GoalID.Get());
2423

2524
return true;

Source/ROSIntegration/Private/Conversion/Messages/actionlib_msgs/ActionlibMsgsGoalStatusArrayConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,7 @@ bool UActionlibMsgsGoalStatusArrayConverter::ConvertOutgoingMessage(TSharedPtr<F
1818
{
1919
auto GoalStatusArray = StaticCastSharedPtr<ROSMessages::actionlib_msgs::GoalStatusArray>(BaseMsg);
2020

21-
*message = new bson_t;
22-
bson_init(*message);
21+
*message = bson_new();
2322
_bson_append_goal_status_array(*message, GoalStatusArray.Get());
2423

2524
return true;

Source/ROSIntegration/Private/Conversion/Messages/actionlib_msgs/ActionlibMsgsGoalStatusArrayConverter.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class ROSINTEGRATION_API UActionlibMsgsGoalStatusArrayConverter : public UBaseMe
4545

4646
static void _bson_append_goal_status_array(bson_t *b, const ROSMessages::actionlib_msgs::GoalStatusArray *g)
4747
{
48-
UStdMsgsHeaderConverter::_bson_append_header(b, &(g->header));
48+
UStdMsgsHeaderConverter::_bson_append_child_header(b, "header", &(g->header));
4949
_bson_append_tarray<ROSMessages::actionlib_msgs::GoalStatus>(b, "status_list", g->status_list, [](bson_t *subb, const char *subKey, ROSMessages::actionlib_msgs::GoalStatus gs)
5050
{
5151
UActionlibMsgsGoalStatusConverter::_bson_append_child_goal_status(subb, subKey, &gs);

Source/ROSIntegration/Private/Conversion/Messages/actionlib_msgs/ActionlibMsgsGoalStatusConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,7 @@ bool UActionlibMsgsGoalStatusConverter::ConvertOutgoingMessage(TSharedPtr<FROSBa
1818
{
1919
auto GoalStatus = StaticCastSharedPtr<ROSMessages::actionlib_msgs::GoalStatus>(BaseMsg);
2020

21-
*message = new bson_t;
22-
bson_init(*message);
21+
*message = bson_new();
2322
_bson_append_goal_status(*message, GoalStatus.Get());
2423

2524
return true;

Source/ROSIntegration/Private/Conversion/Messages/geometry_msgs/GeometryMsgsPointConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,7 @@ bool UGeometryMsgsPointConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg>
1919
{
2020
auto Point = StaticCastSharedPtr<ROSMessages::geometry_msgs::Point>(BaseMsg);
2121

22-
*message = new bson_t;
23-
bson_init(*message);
22+
*message = bson_new();
2423
_bson_append_point(*message, Point.Get());
2524

2625
return true;

Source/ROSIntegration/Private/Conversion/Messages/geometry_msgs/GeometryMsgsPoseConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,7 @@ bool UGeometryMsgsPoseConverter::ConvertOutgoingMessage(TSharedPtr<FROSBaseMsg>
1818
{
1919
auto Pose = StaticCastSharedPtr<ROSMessages::geometry_msgs::Pose>(BaseMsg);
2020

21-
*message = new bson_t;
22-
bson_init(*message);
21+
*message = bson_new();
2322
_bson_append_pose(*message, Pose.Get());
2423

2524
return true;

Source/ROSIntegration/Private/Conversion/Messages/geometry_msgs/GeometryMsgsPoseStampedConverter.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,7 @@ bool UGeometryMsgsPoseStampedConverter::ConvertOutgoingMessage(TSharedPtr<FROSBa
2222
{
2323
auto PoseStamped = StaticCastSharedPtr<ROSMessages::geometry_msgs::PoseStamped>(BaseMsg);
2424

25-
*message = new bson_t;
26-
bson_init(*message);
27-
25+
*message = bson_new();
2826
_bson_append_pose_stamped(*message, PoseStamped.Get());
2927

3028
return true;

Source/ROSIntegration/Private/Conversion/Messages/geometry_msgs/GeometryMsgsPoseStampedConverter.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ class ROSINTEGRATION_API UGeometryMsgsPoseStampedConverter : public UBaseMessage
4343

4444
static void _bson_append_pose_stamped(bson_t *b, const ROSMessages::geometry_msgs::PoseStamped * ps)
4545
{
46-
UStdMsgsHeaderConverter::_bson_append_header(b, &(ps->header));
46+
UStdMsgsHeaderConverter::_bson_append_child_header(b, "header", &(ps->header));
4747
UGeometryMsgsPoseConverter::_bson_append_child_pose(b, "pose", &(ps->pose));
4848
}
4949
};

Source/ROSIntegration/Private/Conversion/Messages/geometry_msgs/GeometryMsgsPoseWithCovarianceConverter.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,7 @@ bool UGeometryMsgsPoseWithCovarianceConverter::ConvertOutgoingMessage(TSharedPtr
1818
{
1919
auto Pose = StaticCastSharedPtr<ROSMessages::geometry_msgs::PoseWithCovariance>(BaseMsg);
2020

21-
*message = new bson_t;
22-
bson_init(*message);
21+
*message = bson_new();
2322
_bson_append_pose_with_covariance(*message, Pose.Get());
2423

2524
return true;

0 commit comments

Comments
 (0)