From dce067df833b2ed4b9eed8aba48ccf9c31db176d Mon Sep 17 00:00:00 2001 From: Steve Nogar Date: Thu, 14 Oct 2021 16:51:10 -0400 Subject: [PATCH] add configurable rtps rate parameter --- .../microRTPS_client_main.cpp | 12 ++++++++- .../micrortps_client/module.yaml | 25 +++++++++++++++++-- 2 files changed, 34 insertions(+), 3 deletions(-) diff --git a/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp b/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp index e5a5af2a1c..1ff41c4682 100644 --- a/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp +++ b/src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp @@ -122,7 +122,17 @@ static int parse_options(int argc, char *argv[]) break; } - case 'm': _options.datarate = strtoul(myoptarg, nullptr, 10); break; + case 'm': { + int datarate = 0; + + if (px4_get_parameter_value(myoptarg, datarate) != 0) { + PX4_ERR("datarate parsing failed"); + } + + _options.datarate = datarate; + + break; + } case 'p': _options.poll_ms = strtoul(myoptarg, nullptr, 10); break; diff --git a/src/modules/micrortps_bridge/micrortps_client/module.yaml b/src/modules/micrortps_bridge/micrortps_client/module.yaml index 608c0c31e6..10049eac32 100644 --- a/src/modules/micrortps_bridge/micrortps_client/module.yaml +++ b/src/modules/micrortps_bridge/micrortps_client/module.yaml @@ -3,15 +3,36 @@ serial_config: - command: | protocol_splitter start ${SERIAL_DEV} mavlink start -d /dev/mavlink -b p:${BAUD_PARAM} -m onboard -r 5000 -x - micrortps_client start -d /dev/rtps -b p:${BAUD_PARAM} -l -1 + micrortps_client start -d /dev/rtps -b p:${BAUD_PARAM} -m p:RTPS_RATE -l -1 port_config_param: name: RTPS_MAV_CONFIG group: RTPS label: MAVLink + FastRTPS - command: | - micrortps_client start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} -l -1 + micrortps_client start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} -m p:RTPS_RATE -l -1 port_config_param: name: RTPS_CONFIG group: RTPS label: FastRTPS +parameters: + - group: RTPS + definitions: + RTPS_RATE: + description: + short: Maximum RTPS data rate + long: | + Configure the maximum sending rate for the RTPS streams in Bytes/sec. + If the configured streams exceed the maximum rate, the sending rate of + each stream is automatically decreased. + + 0 is unlimited. Note this can cause reliability issues + if enough RTPS topics are selected that exceed the + serial bus limit. + + type: int32 + min: 0 + unit: B/s + reboot_required: true + default: 0 +