uxrce_dds_client: add participant configuration parameter

Replaces the localhost-only and custom participant CLI flags
This commit is contained in:
Daniel Mesham 2023-09-27 13:48:38 +02:00 committed by Beat Küng
parent 45fd4d2fb6
commit f02c5319bc
2 changed files with 76 additions and 56 deletions

View File

@ -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

View File

@ -235,10 +235,15 @@ 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);
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<name>%s/px4_micro_xrce_dds</name>%s",
_localhost_only ?
@ -279,14 +284,6 @@ void UxrceddsClient::run()
return;
}
uint16_t participant_req{};
if (_custom_participant) {
participant_req = uxr_buffer_create_participant_ref(&session, reliable_out, participant_id, domain_id,
"px4_participant", UXR_REPLACE);
} else {
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<uint8_t>(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:<param_name>)", true);
PRINT_MODULE_USAGE_PARAM_STRING('h', nullptr, "<IP>", "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();