Browse Source

add configurable rtps rate parameter

master
Steve Nogar 3 years ago committed by Nuno Marques
parent
commit
dce067df83
  1. 12
      src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp
  2. 25
      src/modules/micrortps_bridge/micrortps_client/module.yaml

12
src/modules/micrortps_bridge/micrortps_client/microRTPS_client_main.cpp

@ -122,7 +122,17 @@ static int parse_options(int argc, char *argv[]) @@ -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;

25
src/modules/micrortps_bridge/micrortps_client/module.yaml

@ -3,15 +3,36 @@ serial_config: @@ -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

Loading…
Cancel
Save