Skip to content

Commit

Permalink
Use the macros from Cyclone DDS to work with sample payload when usin…
Browse files Browse the repository at this point in the history
…g SHM (ros2#300)

Signed-off-by: Sumanth Nirmal <sumanth.724@gmail.com>
  • Loading branch information
sumanth-nirmal authored and clalancette committed May 18, 2022
1 parent 50e523c commit c877490
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 15 deletions.
8 changes: 4 additions & 4 deletions rmw_cyclonedds_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1611,7 +1611,7 @@ static rmw_ret_t publish_loaned_int(
// if the publisher allow loaning
if (cdds_publisher->is_loaning_available) {
auto d = std::make_unique<serdata_rmw>(cdds_publisher->sertype, ddsi_serdata_kind::SDK_DATA);
d->iox_chunk = SHIFT_BACK_ICEORYX_HEADER(ros_message);
d->iox_chunk = SHIFT_BACK_TO_ICEORYX_HEADER(ros_message);
if (dds_writecdr(cdds_publisher->enth, d.release()) >= 0) {
return RMW_RET_OK;
} else {
Expand Down Expand Up @@ -2304,7 +2304,7 @@ static rmw_ret_t borrow_loaned_message_int(
dds_data_allocator_init(cdds_publisher->enth, &cdds_publisher->data_allocator);
// allocate memory for message + header
auto sample_size = rmw_cyclonedds_cpp::get_message_size(type_support);
auto chunk_size = GET_ICEORYX_CHUNK_SIZE(sample_size);
auto chunk_size = DETERMINE_ICEORYX_CHUNK_SIZE(sample_size);
auto chunk_ptr = dds_data_allocator_alloc(
&cdds_publisher->data_allocator, chunk_size);
RMW_CHECK_FOR_NULL_WITH_MSG(
Expand Down Expand Up @@ -2371,7 +2371,7 @@ static rmw_ret_t return_loaned_message_from_publisher_int(
// free the message memory
dds_data_allocator_free(
&cdds_publisher->data_allocator,
SHIFT_BACK_ICEORYX_HEADER(loaned_message));
SHIFT_BACK_TO_ICEORYX_HEADER(loaned_message));
// fini data collector
dds_data_allocator_fini(&cdds_publisher->data_allocator);
return RMW_RET_OK;
Expand Down Expand Up @@ -3165,7 +3165,7 @@ static rmw_ret_t return_loaned_message_from_subscription_int(
if (cdds_subscription->is_loaning_available) {
dds_data_allocator_t data_allocator;
dds_data_allocator_init(cdds_subscription->enth, &data_allocator);
dds_data_allocator_free(&data_allocator, SHIFT_BACK_ICEORYX_HEADER(loaned_message));
dds_data_allocator_free(&data_allocator, SHIFT_BACK_TO_ICEORYX_HEADER(loaned_message));
dds_data_allocator_fini(&data_allocator);
} else {
RMW_SET_ERROR_MSG("returning loan for a non fixed type is not allowed");
Expand Down
13 changes: 2 additions & 11 deletions rmw_cyclonedds_cpp/src/serdata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@
#include "bytewise.hpp"
#include "dds/dds.h"
#include "dds/ddsi/ddsi_serdata.h"
#ifdef DDS_HAS_SHM
#include "dds/ddsi/q_xmsg.h"
#endif // DDS_HAS_SHM

#if !DDS_HAS_DDSI_SERTYPE
#define ddsi_sertype ddsi_sertopic
Expand All @@ -30,17 +32,6 @@
#define sertype_rmw_ops sertopic_rmw_ops
#endif

#ifdef DDS_HAS_SHM
#define GET_ICEORYX_CHUNK_SIZE(sample_size) \
(uint32_t) (sizeof(iceoryx_header_t) + 8 - (sizeof(iceoryx_header_t) % 8) + (sample_size))
#define SHIFT_PAST_ICEORYX_HEADER(chunk) \
(static_cast<void *>((reinterpret_cast<char *>(chunk)) + \
sizeof(iceoryx_header_t) + 8 - (sizeof(iceoryx_header_t) % 8)))
#define SHIFT_BACK_ICEORYX_HEADER(chunk) \
(static_cast<void *>((reinterpret_cast<char *>(chunk)) - \
sizeof(iceoryx_header_t) - 8 + (sizeof(iceoryx_header_t) % 8)))
#endif // DDS_HAS_SHM

namespace rmw_cyclonedds_cpp
{
class BaseCDRWriter;
Expand Down

0 comments on commit c877490

Please sign in to comment.