Skip to content

Commit

Permalink
Durability QoS (#241)
Browse files Browse the repository at this point in the history
* Durability QoS

* Uncrustified

* Remove default
  • Loading branch information
pablogs9 authored May 17, 2021
1 parent 29e709e commit 984d0b9
Show file tree
Hide file tree
Showing 4 changed files with 54 additions and 12 deletions.
4 changes: 2 additions & 2 deletions examples/BinaryEntityCreation/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -96,15 +96,15 @@ int main(

uxrObjectId datawriter_id = uxr_object_id(0x01, UXR_DATAWRITER_ID);
uint16_t datawriter_req = uxr_buffer_create_datawriter_bin(&session, reliable_out, datawriter_id, publisher_id,
topic_id, 1, 1, 1, UXR_REPLACE);
topic_id, 1, 1, UXR_DURABILITY_TRANSIENT_LOCAL, UXR_REPLACE);

uxrObjectId subscriber_id = uxr_object_id(0x01, UXR_SUBSCRIBER_ID);
uint16_t subscriber_req = uxr_buffer_create_subscriber_bin(&session, reliable_out, subscriber_id, participant_id,
UXR_REPLACE);

uxrObjectId datareader_id = uxr_object_id(0x01, UXR_DATAREADER_ID);
uint16_t datareader_req = uxr_buffer_create_datareader_bin(&session, reliable_out, datareader_id, subscriber_id,
topic_id, 1, 1, 1, UXR_REPLACE);
topic_id, 1, 1, UXR_DURABILITY_TRANSIENT_LOCAL, UXR_REPLACE);

// Send create entities message and wait its status
uint16_t requests[] = {
Expand Down
16 changes: 14 additions & 2 deletions include/uxr/client/core/session/create_entities_bin.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,18 @@ UXRDLLAPI uint16_t uxr_buffer_create_subscriber_bin(
uxrObjectId participant_id,
uint8_t mode);

/**
* The enum that identifies the durability of the QoS of the DDS entity.
*/

typedef enum uxrQoSDurability
{
UXR_DURABILITY_VOLATILE = 0,
UXR_DURABILITY_TRANSIENT_LOCAL,
UXR_DURABILITY_TRANSIENT,
UXR_DURABILITY_PERSISTENT
} uxrQoSDurability;

/**
* @brief Buffers into the stream identified by `stream_id` an XRCE CREATE submessage with an XRCE DataWriter payload.
* The submessage will be sent when `uxr_flash_output_streams` or `uxr_run_session` function are called.
Expand Down Expand Up @@ -142,7 +154,7 @@ UXRDLLAPI uint16_t uxr_buffer_create_datawriter_bin(
uxrObjectId topic_id,
bool reliable,
bool keep_last,
bool transient_local,
uxrQoSDurability durability,
uint8_t mode);

/**
Expand Down Expand Up @@ -172,7 +184,7 @@ UXRDLLAPI uint16_t uxr_buffer_create_datareader_bin(
uxrObjectId topic_id,
bool reliable,
bool keep_last,
bool transient_local,
uxrQoSDurability durability,
uint8_t mode);
/**
* @brief Buffers into the stream identified by `stream_id` an XRCE CREATE submessage with an XRCE Requester payload.
Expand Down
42 changes: 36 additions & 6 deletions src/c/core/session/create_entities_bin.c
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
#include <uxr/client/core/session/create_entities_bin.h>

#include <uxr/client/core/type/xrce_types.h>

#include "common_create_entities_internal.h"
Expand Down Expand Up @@ -122,7 +124,7 @@ uint16_t uxr_buffer_create_datawriter_bin(
uxrObjectId topic_id,
bool reliable,
bool keep_last,
bool transient_local,
uxrQoSDurability durability,
uint8_t mode)
{
CREATE_Payload payload;
Expand All @@ -148,9 +150,23 @@ uint16_t uxr_buffer_create_datawriter_bin(
{
datawriter.qos.base.qos_flags |= is_history_keep_last;
}
if (transient_local)

switch (durability)
{
datawriter.qos.base.qos_flags |= is_durability_transient_local;
case UXR_DURABILITY_VOLATILE:
// datawriter.qos.base.qos_flags all flags zeroed
break;
case UXR_DURABILITY_TRANSIENT_LOCAL:
datawriter.qos.base.qos_flags |= is_durability_transient_local;
break;
case UXR_DURABILITY_TRANSIENT:
datawriter.qos.base.qos_flags |= is_durability_transient;
break;
case UXR_DURABILITY_PERSISTENT:
datawriter.qos.base.qos_flags |= is_durability_persistent;
break;
default:
break;
}

UXR_ADD_SHARED_MEMORY_ENTITY_BIN(session, object_id, &datawriter);
Expand All @@ -172,7 +188,7 @@ uint16_t uxr_buffer_create_datareader_bin(
uxrObjectId topic_id,
bool reliable,
bool keep_last,
bool transient_local,
uxrQoSDurability durability,
uint8_t mode)
{
CREATE_Payload payload;
Expand All @@ -199,9 +215,23 @@ uint16_t uxr_buffer_create_datareader_bin(
{
datareader.qos.base.qos_flags |= is_history_keep_last;
}
if (transient_local)

switch (durability)
{
datareader.qos.base.qos_flags |= is_durability_transient_local;
case UXR_DURABILITY_VOLATILE:
// datawriter.qos.base.qos_flags all flags zeroed
break;
case UXR_DURABILITY_TRANSIENT_LOCAL:
datareader.qos.base.qos_flags |= is_durability_transient_local;
break;
case UXR_DURABILITY_TRANSIENT:
datareader.qos.base.qos_flags |= is_durability_transient;
break;
case UXR_DURABILITY_PERSISTENT:
datareader.qos.base.qos_flags |= is_durability_persistent;
break;
default:
break;
}

UXR_ADD_SHARED_MEMORY_ENTITY_BIN(session, object_id, &datareader);
Expand Down
4 changes: 2 additions & 2 deletions test/shared_memory/SharedMemory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class SharedMemoryTest : public ::testing::TestWithParam<XRCECreationMode>
uxr_buffer_create_topic_bin(&session, output_besteffort, topic_id, participant_id,
topic.c_str(), type.c_str(), UXR_REPLACE);
uxr_buffer_create_datawriter_bin(&session, output_besteffort, datawriter_id, publisher_id, topic_id, 1,
1, 1, UXR_REPLACE);
1, UXR_DURABILITY_TRANSIENT_LOCAL, UXR_REPLACE);
break;
default:
// ASSERT_TRUE(0);
Expand Down Expand Up @@ -127,7 +127,7 @@ class SharedMemoryTest : public ::testing::TestWithParam<XRCECreationMode>
uxr_buffer_create_topic_bin(&session, output_besteffort, topic_id, participant_id,
topic.c_str(), type.c_str(), UXR_REPLACE);
uxr_buffer_create_datareader_bin(&session, output_besteffort, datareader_id, subscriber_id, topic_id, 1,
1, 1, UXR_REPLACE);
1, UXR_DURABILITY_TRANSIENT_LOCAL, UXR_REPLACE);
break;
default:
// ASSERT_TRUE(0);
Expand Down

0 comments on commit 984d0b9

Please sign in to comment.