From f02c5319bcced01e23203e2fe8a8ae13ee497ff3 Mon Sep 17 00:00:00 2001 From: Daniel Mesham Date: Wed, 27 Sep 2023 13:48:38 +0200 Subject: [PATCH] uxrce_dds_client: add participant configuration parameter Replaces the localhost-only and custom participant CLI flags --- src/modules/uxrce_dds_client/module.yaml | 20 ++++ .../uxrce_dds_client/uxrce_dds_client.cpp | 112 +++++++++--------- 2 files changed, 76 insertions(+), 56 deletions(-) diff --git a/src/modules/uxrce_dds_client/module.yaml b/src/modules/uxrce_dds_client/module.yaml index 5fcc65d2ce..26d79d92a2 100644 --- a/src/modules/uxrce_dds_client/module.yaml +++ b/src/modules/uxrce_dds_client/module.yaml @@ -65,6 +65,26 @@ parameters: default: 2130706433 requires_ethernet: true + UXRCE_DDS_PTCFG: + description: + short: uXRCE-DDS participant configuration + long: | + Set the participant configuration on the Agent's system. + 0: Use the default configuration. + 1: Restrict messages to localhost + (use in combination with ROS_LOCALHOST_ONLY=1). + 2: Use a custom participant with the profile name "px4_participant". + category: System + reboot_required: true + type: enum + values: + 0: Default + 1: Localhost-only + 2: Custom participant + min: 0 + max: 2 + default: 0 + UXRCE_DDS_SYNCT: description: short: Enable uXRCE-DDS timestamp synchronization diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index 9b00379a26..c2274bf915 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -235,58 +235,55 @@ void UxrceddsClient::run() uint16_t domain_id = _param_xrce_dds_dom_id.get(); - // const char *participant_name = "px4_micro_xrce_dds"; - // uint16_t participant_req = uxr_buffer_create_participant_bin(&session, reliable_out, participant_id, domain_id, - // participant_name, UXR_REPLACE); - - char participant_xml[PARTICIPANT_XML_SIZE]; - int ret = snprintf(participant_xml, PARTICIPANT_XML_SIZE, "%s%s/px4_micro_xrce_dds%s", - _localhost_only ? - "" - "" - "" - "" - "udp_localhost" - "UDPv4" - "
127.0.0.1
" - "
" - "
" - "
" - "" - "" - : - "" - "" - "", - _client_namespace != nullptr ? - _client_namespace - : - "", - _localhost_only ? - "false" - "udp_localhost" - "" - "" - "" - : - "" - "" - "
" - ); - - if (ret < 0 || ret >= PARTICIPANT_XML_SIZE) { - PX4_ERR("create entities failed: namespace too long"); - return; - } - - uint16_t participant_req{}; if (_custom_participant) { + // Create participant by reference (XML not required) participant_req = uxr_buffer_create_participant_ref(&session, reliable_out, participant_id, domain_id, "px4_participant", UXR_REPLACE); } else { + // Construct participant XML and create participant by XML + char participant_xml[PARTICIPANT_XML_SIZE]; + int ret = snprintf(participant_xml, PARTICIPANT_XML_SIZE, "%s%s/px4_micro_xrce_dds%s", + _localhost_only ? + "" + "" + "" + "" + "udp_localhost" + "UDPv4" + "
127.0.0.1
" + "
" + "
" + "
" + "" + "" + : + "" + "" + "", + _client_namespace != nullptr ? + _client_namespace + : + "", + _localhost_only ? + "false" + "udp_localhost" + "" + "" + "" + : + "" + "" + "
" + ); + + if (ret < 0 || ret >= PARTICIPANT_XML_SIZE) { + PX4_ERR("create entities failed: namespace too long"); + return; + } + participant_req = uxr_buffer_create_participant_xml(&session, reliable_out, participant_id, domain_id, participant_xml, UXR_REPLACE); } @@ -628,7 +625,7 @@ UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[]) const char *client_namespace = nullptr;//"px4"; - while ((ch = px4_getopt(argc, argv, "t:d:b:h:p:lcn:", &myoptind, &myoptarg)) != EOF) { + while ((ch = px4_getopt(argc, argv, "t:d:b:h:p:n:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 't': if (!strcmp(myoptarg, "serial")) { @@ -665,14 +662,6 @@ UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[]) case 'p': snprintf(port, PORT_MAX_LENGTH, "%s", myoptarg); break; - - case 'l': - localhost_only = true; - break; - - case 'c': - custom_participant = true; - break; #endif // UXRCE_DDS_CLIENT_UDP case 'n': @@ -715,6 +704,19 @@ UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[]) static_cast(ip_i & 0xff)); } + int32_t participant_config = 0; + param_get(param_find("UXRCE_DDS_PTCFG"), &participant_config); + + switch (participant_config) { + case 1: + localhost_only = true; + break; + + case 2: + custom_participant = true; + break; + } + #endif // UXRCE_DDS_CLIENT_UDP if (error_flag) { @@ -764,8 +766,6 @@ $ uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 PRINT_MODULE_USAGE_PARAM_INT('b', 0, 0, 3000000, "Baudrate (can also be p:)", true); PRINT_MODULE_USAGE_PARAM_STRING('h', nullptr, "", "Agent IP. If not provided, defaults to UXRCE_DDS_AG_IP", true); PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 65535, "Agent listening port. If not provided, defaults to UXRCE_DDS_PRT", true); - PRINT_MODULE_USAGE_PARAM_FLAG('l', "Restrict to localhost (use in combination with ROS_LOCALHOST_ONLY=1)", true); - PRINT_MODULE_USAGE_PARAM_FLAG('c', "Use custom participant config (profile_name=\"px4_participant\")", true); PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, nullptr, "Client DDS namespace", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS();