microdds_client: rename to uxrce_dds_client

| | old version | new version (second proposal) |
|-|-|-|
| module name | `microdds_client` | **`uxrce_dds_client`** |
| strings / comments about the module | non consistent | **UXRCE-DDS Client** |
| menuconfig option | `MODULES_MICRODDS_CLIENT` | **`MODULES_UXRCE_DDS_CLIENT`** |
| module parameters group name | `Micro XRCE-DDS` | **UXRCE-DDS Client** |
| module parameters name prefix | `XRCE_DDS_` | `UXRCE_DDS_` |
| module class name | `MicroddsClient` | **`UxrceddsClient`** |
|`init.d/rcS` whenever the module is mentioned | `microdds` | **`uxrce_dds`** |
| main doc page name | XRCE-DDS (PX4-FastDDS Bridge) | **uXRCE-DDS (PX4-micro XRCE-DDS Bridge)**|
| environment variable to have custom namespace in simulation | PX4_MICRODDS_NS | **PX4_UXRCE_DDS_NS** |

Signed-off-by: Beniamino Pozzan <beniamino.pozzan@phd.unipd.it>
This commit is contained in:
Beniamino Pozzan
2023-04-20 18:06:06 -07:00
committed by Ramon Roche
parent 1d4b66fcbc
commit 9e5420bbbd
52 changed files with 121 additions and 122 deletions
-5
View File
@@ -1,5 +0,0 @@
menuconfig MODULES_MICRODDS_CLIENT
bool "microdds_client"
default n
---help---
Enable support for the MicroDDS Client
@@ -32,7 +32,7 @@
############################################################################
if(${CMAKE_VERSION} VERSION_LESS "3.11")
message(WARNING "skipping microdds_client, Micro-XRCE-DDS-Client needs to be fixed to work with CMAKE_VERSION ${CMAKE_VERSION}")
message(WARNING "skipping uxrce_dds_client, Micro-XRCE-DDS-Client needs to be fixed to work with CMAKE_VERSION ${CMAKE_VERSION}")
else()
px4_add_git_submodule(TARGET git_micro_xrce_dds_client PATH "${CMAKE_CURRENT_LIST_DIR}/Micro-XRCE-DDS-Client")
@@ -130,8 +130,8 @@ else()
add_custom_target(topic_bridge_files DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/dds_topics.h)
px4_add_module(
MODULE modules__microdds_client
MAIN microdds_client
MODULE modules__uxrce_dds_client
MAIN uxrce_dds_client
STACK_MAIN 9000
INCLUDES
${CMAKE_CURRENT_SOURCE_DIR}
@@ -140,8 +140,8 @@ else()
${MAX_CUSTOM_OPT_LEVEL}
SRCS
${CMAKE_CURRENT_BINARY_DIR}/dds_topics.h
microdds_client.cpp
microdds_client.h
uxrce_dds_client.cpp
uxrce_dds_client.h
DEPENDS
microxrceddsclient
libmicroxrceddsclient
+5
View File
@@ -0,0 +1,5 @@
menuconfig MODULES_UXRCE_DDS_CLIENT
bool "uxrce_dds_client"
default n
---help---
Enable support for the UXRCE-DDS Client
@@ -1,6 +1,6 @@
#####
#
# This file maps all the topics that are to be used on the micro DDS client.
# This file maps all the topics that are to be used on the uXRCE-DDS client.
#
#####
publications:
@@ -53,7 +53,7 @@ parser.add_argument("-t", "--template_file", dest='template_file', type=str,
help="DDS topics template file")
parser.add_argument("-u", "--client-outdir", dest='clientdir', type=str,
help="Client output dir, by default using relative path 'src/modules/microdds_client'", default=None)
help="Client output dir, by default using relative path 'src/modules/uxrce_dds_client'", default=None)
if len(sys.argv) <= 1:
parser.print_usage()
@@ -1,36 +1,36 @@
module_name: Micro XRCE-DDS
module_name: UXRCE-DDS Client
serial_config:
- command: |
if [ $SERIAL_DEV != ethernet ]; then
set XRCE_DDS_ARGS "-t serial -d ${SERIAL_DEV} -b p:${BAUD_PARAM}"
set UXRCE_DDS_ARGS "-t serial -d ${SERIAL_DEV} -b p:${BAUD_PARAM}"
else
set XRCE_DDS_ARGS "-t udp"
set UXRCE_DDS_ARGS "-t udp"
fi
microdds_client start ${XRCE_DDS_ARGS}
uxrce_dds_client start ${UXRCE_DDS_ARGS}
port_config_param:
name: XRCE_DDS_CFG
group: Micro XRCE-DDS
name: UXRCE_DDS_CFG
group: UXRCE-DDS Client
supports_networking: true
parameters:
- group: Micro XRCE-DDS
- group: UXRCE-DDS Client
definitions:
XRCE_DDS_DOM_ID:
UXRCE_DDS_DOM_ID:
description:
short: XRCE DDS domain ID
long: XRCE DDS domain ID
short: uXRCE-DDS domain ID
long: uXRCE-DDS domain ID
category: System
type: int32
reboot_required: true
default: 0
XRCE_DDS_KEY:
UXRCE_DDS_KEY:
description:
short: XRCE DDS Session key
short: uXRCE-DDS Session key
long: |
XRCE DDS key, must be different from zero.
uXRCE-DDS key, must be different from zero.
In a single agent - multi client configuration, each client
must have a unique session key.
category: System
@@ -38,11 +38,11 @@ parameters:
reboot_required: true
default: 1
XRCE_DDS_PRT:
UXRCE_DDS_PRT:
description:
short: Micro DDS UDP Port
short: uXRCE-DDS UDP Port
long: |
If ethernet enabled and selected as configuration for micro DDS,
If ethernet enabled and selected as configuration for uXRCE-DDS,
selected udp port will be set and used.
type: int32
min: 0
@@ -51,11 +51,11 @@ parameters:
default: 8888
requires_ethernet: true
XRCE_DDS_AG_IP:
UXRCE_DDS_AG_IP:
description:
short: Micro DDS Agent IP address
short: uXRCE-DDS Agent IP address
long: |
If ethernet enabled and selected as configuration for micro DDS,
If ethernet enabled and selected as configuration for uXRCE-DDS,
selected Agent IP address will be set and used.
Decimal dot notation is not supported. IP address must be provided
in int32 format. For example, 192.168.1.2 is mapped to -1062731518;
@@ -35,7 +35,7 @@
#include <px4_platform_common/cli.h>
#include <px4_platform_common/posix.h>
#include "microdds_client.h"
#include "uxrce_dds_client.h"
#include <uxr/client/client.h>
#include <uxr/client/util/ping.h>
@@ -47,7 +47,7 @@
#include <unistd.h>
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
# define MICRODDS_CLIENT_UDP 1
# define UXRCE_DDS_CLIENT_UDP 1
#endif
#define STREAM_HISTORY 4
@@ -79,7 +79,7 @@ void on_time(uxrSession *session, int64_t current_time, int64_t received_timesta
}
}
MicroddsClient::MicroddsClient(Transport transport, const char *device, int baudrate, const char *agent_ip,
UxrceddsClient::UxrceddsClient(Transport transport, const char *device, int baudrate, const char *agent_ip,
const char *port, bool localhost_only, bool custom_participant, const char *client_namespace) :
ModuleParams(nullptr),
_localhost_only(localhost_only), _custom_participant(custom_participant),
@@ -120,7 +120,7 @@ MicroddsClient::MicroddsClient(Transport transport, const char *device, int baud
} else if (transport == Transport::Udp) {
#if defined(MICRODDS_CLIENT_UDP)
#if defined(UXRCE_DDS_CLIENT_UDP)
_transport_udp = new uxrUDPTransport();
strncpy(_port, port, PORT_MAX_LENGTH - 1);
strncpy(_agent_ip, agent_ip, AGENT_IP_MAX_LENGTH - 1);
@@ -141,7 +141,7 @@ MicroddsClient::MicroddsClient(Transport transport, const char *device, int baud
}
}
MicroddsClient::~MicroddsClient()
UxrceddsClient::~UxrceddsClient()
{
delete _subs;
delete _pubs;
@@ -157,7 +157,7 @@ MicroddsClient::~MicroddsClient()
}
}
void MicroddsClient::run()
void UxrceddsClient::run()
{
if (!_comm) {
PX4_ERR("init failed");
@@ -386,7 +386,7 @@ void MicroddsClient::run()
}
}
int MicroddsClient::setBaudrate(int fd, unsigned baud)
int UxrceddsClient::setBaudrate(int fd, unsigned baud)
{
int speed;
@@ -523,14 +523,14 @@ int MicroddsClient::setBaudrate(int fd, unsigned baud)
return 0;
}
int MicroddsClient::custom_command(int argc, char *argv[])
int UxrceddsClient::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int MicroddsClient::task_spawn(int argc, char *argv[])
int UxrceddsClient::task_spawn(int argc, char *argv[])
{
_task_id = px4_task_spawn_cmd("microdds_client",
_task_id = px4_task_spawn_cmd("uxrce_dds_client",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
PX4_STACK_ADJUSTED(10000),
@@ -545,10 +545,10 @@ int MicroddsClient::task_spawn(int argc, char *argv[])
return 0;
}
int MicroddsClient::print_status()
int UxrceddsClient::print_status()
{
PX4_INFO("Running, %s", _connected ? "connected" : "disconnected");
#if defined(MICRODDS_CLIENT_UDP)
#if defined(UXRCE_DDS_CLIENT_UDP)
if (_transport_udp != nullptr) {
PX4_INFO("Using transport: udp");
@@ -571,7 +571,7 @@ int MicroddsClient::print_status()
return 0;
}
MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[])
{
bool error_flag = false;
int myoptind = 1;
@@ -581,7 +581,7 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
char port[PORT_MAX_LENGTH] = {0};
char agent_ip[AGENT_IP_MAX_LENGTH] = {0};
#if defined(MICRODDS_CLIENT_UDP)
#if defined(UXRCE_DDS_CLIENT_UDP)
Transport transport = Transport::Udp;
#else
Transport transport = Transport::Serial;
@@ -622,7 +622,7 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
break;
#if defined(MICRODDS_CLIENT_UDP)
#if defined(UXRCE_DDS_CLIENT_UDP)
case 'h':
snprintf(agent_ip, AGENT_IP_MAX_LENGTH, "%s", myoptarg);
@@ -639,7 +639,7 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
case 'c':
custom_participant = true;
break;
#endif // MICRODDS_CLIENT_UDP
#endif // UXRCE_DDS_CLIENT_UDP
case 'n':
client_namespace = myoptarg;
@@ -656,12 +656,12 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
}
}
#if defined(MICRODDS_CLIENT_UDP)
#if defined(UXRCE_DDS_CLIENT_UDP)
if (port[0] == '\0') {
// no port specified, use XRCE_DDS_PRT
// no port specified, use UXRCE_DDS_PRT
int32_t port_i = 0;
param_get(param_find("XRCE_DDS_PRT"), &port_i);
param_get(param_find("UXRCE_DDS_PRT"), &port_i);
if (port_i < 0 || port_i > 65535) {
PX4_ERR("port must be between 0 and 65535");
@@ -672,16 +672,16 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
}
if (agent_ip[0] == '\0') {
// no agent ip specified, use XRCE_DDS_AG_IP
// no agent ip specified, use UXRCE_DDS_AG_IP
int32_t ip_i = 0;
param_get(param_find("XRCE_DDS_AG_IP"), &ip_i);
param_get(param_find("UXRCE_DDS_AG_IP"), &ip_i);
snprintf(agent_ip, AGENT_IP_MAX_LENGTH, "%u.%u.%u.%u", static_cast<uint8_t>(((ip_i) >> 24) & 0xff),
static_cast<uint8_t>(((ip_i) >> 16) & 0xff),
static_cast<uint8_t>(((ip_i) >> 8) & 0xff),
static_cast<uint8_t>(ip_i & 0xff));
}
#endif // MICRODDS_CLIENT_UDP
#endif // UXRCE_DDS_CLIENT_UDP
if (error_flag) {
return nullptr;
@@ -694,11 +694,11 @@ MicroddsClient *MicroddsClient::instantiate(int argc, char *argv[])
}
}
return new MicroddsClient(transport, device, baudrate, agent_ip, port, localhost_only, custom_participant,
return new UxrceddsClient(transport, device, baudrate, agent_ip, port, localhost_only, custom_participant,
client_namespace);
}
int MicroddsClient::print_usage(const char *reason)
int UxrceddsClient::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
@@ -707,20 +707,20 @@ int MicroddsClient::print_usage(const char *reason)
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
MicroDDS Client used to communicate uORB topics with an Agent over serial or UDP.
UXRCE-DDS Client used to communicate uORB topics with an Agent over serial or UDP.
### Examples
$ microdds_client start -t serial -d /dev/ttyS3 -b 921600
$ microdds_client start -t udp -h 127.0.0.1 -p 15555
$ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600
$ uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("microdds_client", "system");
PRINT_MODULE_USAGE_NAME("uxrce_dds_client", "system");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAM_STRING('t', "udp", "serial|udp", "Transport protocol", true);
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<file:dev>", "serial device", true);
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 XRCE_DDS_AG_IP", true);
PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 65535, "Agent listening port. If not provided, defaults to XRCE_DDS_PRT", 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);
@@ -729,7 +729,7 @@ $ microdds_client start -t udp -h 127.0.0.1 -p 15555
return 0;
}
extern "C" __EXPORT int microdds_client_main(int argc, char *argv[])
extern "C" __EXPORT int uxrce_dds_client_main(int argc, char *argv[])
{
return MicroddsClient::main(argc, argv);
return UxrceddsClient::main(argc, argv);
}
@@ -36,11 +36,11 @@
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <src/modules/microdds_client/dds_topics.h>
#include <src/modules/uxrce_dds_client/dds_topics.h>
#include <lib/timesync/Timesync.hpp>
class MicroddsClient : public ModuleBase<MicroddsClient>, public ModuleParams
class UxrceddsClient : public ModuleBase<UxrceddsClient>, public ModuleParams
{
public:
enum class Transport {
@@ -48,16 +48,16 @@ public:
Udp
};
MicroddsClient(Transport transport, const char *device, int baudrate, const char *host, const char *port,
UxrceddsClient(Transport transport, const char *device, int baudrate, const char *host, const char *port,
bool localhost_only, bool custom_participant, const char *client_namespace);
~MicroddsClient();
~UxrceddsClient();
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static MicroddsClient *instantiate(int argc, char *argv[]);
static UxrceddsClient *instantiate(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
@@ -104,8 +104,7 @@ private:
Timesync _timesync{timesync_status_s::SOURCE_PROTOCOL_DDS};
DEFINE_PARAMETERS(
(ParamInt<px4::params::XRCE_DDS_DOM_ID>) _param_xrce_dds_dom_id,
(ParamInt<px4::params::XRCE_DDS_KEY>) _param_xrce_key
(ParamInt<px4::params::UXRCE_DDS_DOM_ID>) _param_xrce_dds_dom_id,
(ParamInt<px4::params::UXRCE_DDS_KEY>) _param_xrce_key
)
};