Skip to content

Commit ff1b849

Browse files
Fix max lenght in UDP port string (backport #315) (#320)
* Fix max lenght in UDP port string (#315) * Fix max lenght in UDP port string * Fix CI Signed-off-by: Pablo Garrido <pablogs9@gmail.com> * Update * Linting * Update * Fix uncrustify --------- Signed-off-by: Pablo Garrido <pablogs9@gmail.com> (cherry picked from commit aa15666) # Conflicts: # .github/workflows/ci.yml * Fix conflicts --------- Co-authored-by: Pablo Garrido <pablogs9@gmail.com>
1 parent 554445f commit ff1b849

4 files changed

Lines changed: 4 additions & 5 deletions

File tree

.github/workflows/ci.yml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,15 +23,14 @@ jobs:
2323

2424
- name: Download dependencies
2525
run: |
26-
apt update && apt install -y python3-pip git python3-rosdep python3-colcon-common-extensions curl ros-$ROS_DISTRO-performance-test-fixture
26+
apt update && apt install -y python3-pip git python3-rosdep python3-colcon-common-extensions curl ros-$ROS_DISTRO-performance-test-fixture gcovr
2727
git clone -b ros2 https://github.com/eProsima/Micro-CDR src/Micro-CDR
2828
git clone -b ros2 https://github.com/eProsima/Micro-XRCE-DDS-Client src/Micro-XRCE-DDS-Client
2929
git clone -b jazzy https://github.com/micro-ROS/rosidl_typesupport_microxrcedds src/rosidl_typesupport_microxrcedds
3030
git clone -b jazzy https://github.com/ros2/rmw src/rmw
3131
touch src/rosidl_typesupport_microxrcedds/test/COLCON_IGNORE
3232
3333
# Install coverage tools
34-
apt install -y gcovr
3534
. /opt/ros/$ROS_DISTRO/setup.sh
3635
rosdep init && rosdep update
3736
rosdep install --from-paths src -r

rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ extern "C"
4949
#elif defined(RMW_UXRCE_TRANSPORT_IPV6)
5050
#define MAX_IP_LEN 39
5151
#endif // ifdef RMW_UXRCE_TRANSPORT_IPV4
52-
#define MAX_PORT_LEN 5
52+
#define MAX_PORT_LEN 6 // uint16_t max size + NULL-end string
5353
#define MAX_SERIAL_DEVICE 50
5454

5555
typedef struct rmw_uxrce_transport_params_t

rmw_microxrcedds_c/src/rmw_init.c

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ rmw_init_options_init(
9292
return RMW_RET_INVALID_ARGUMENT;
9393
}
9494

95-
if (strlen(RMW_UXRCE_DEFAULT_PORT) <= MAX_PORT_LEN) {
95+
if (strlen(RMW_UXRCE_DEFAULT_PORT) < MAX_PORT_LEN) {
9696
snprintf(
9797
init_options->impl->transport_params.agent_port,
9898
MAX_PORT_LEN, "%s", RMW_UXRCE_DEFAULT_PORT);

rmw_microxrcedds_c/src/rmw_microros/init_options.c

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ rmw_ret_t rmw_uros_options_set_udp_address(
9797
return RMW_RET_INVALID_ARGUMENT;
9898
}
9999

100-
if (port != NULL && strlen(port) <= MAX_PORT_LEN) {
100+
if (port != NULL && strlen(port) < MAX_PORT_LEN) {
101101
snprintf(rmw_options->impl->transport_params.agent_port, MAX_PORT_LEN, "%s", port);
102102
} else {
103103
RMW_UROS_TRACE_MESSAGE("default port configuration error")

0 commit comments

Comments
 (0)