diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index b7cda287..3d3ea0f8 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -23,7 +23,7 @@ jobs: - name: Download dependencies run: | - apt update && apt install -y python3-pip git python3-rosdep python3-colcon-common-extensions curl ros-$ROS_DISTRO-performance-test-fixture + apt update && apt install -y python3-pip git python3-rosdep python3-colcon-common-extensions curl ros-$ROS_DISTRO-performance-test-fixture gcovr git clone -b ros2 https://github.com/eProsima/Micro-CDR src/Micro-CDR git clone -b ros2 https://github.com/eProsima/Micro-XRCE-DDS-Client src/Micro-XRCE-DDS-Client git clone -b jazzy https://github.com/micro-ROS/rosidl_typesupport_microxrcedds src/rosidl_typesupport_microxrcedds @@ -31,7 +31,6 @@ jobs: touch src/rosidl_typesupport_microxrcedds/test/COLCON_IGNORE # Install coverage tools - apt install -y gcovr . /opt/ros/$ROS_DISTRO/setup.sh rosdep init && rosdep update rosdep install --from-paths src -r diff --git a/rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h b/rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h index 3d3e3383..2568f94a 100644 --- a/rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h +++ b/rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h @@ -49,7 +49,7 @@ extern "C" #elif defined(RMW_UXRCE_TRANSPORT_IPV6) #define MAX_IP_LEN 39 #endif // ifdef RMW_UXRCE_TRANSPORT_IPV4 -#define MAX_PORT_LEN 5 +#define MAX_PORT_LEN 6 // uint16_t max size + NULL-end string #define MAX_SERIAL_DEVICE 50 typedef struct rmw_uxrce_transport_params_t diff --git a/rmw_microxrcedds_c/src/rmw_init.c b/rmw_microxrcedds_c/src/rmw_init.c index 83121734..e5402f4b 100644 --- a/rmw_microxrcedds_c/src/rmw_init.c +++ b/rmw_microxrcedds_c/src/rmw_init.c @@ -92,7 +92,7 @@ rmw_init_options_init( return RMW_RET_INVALID_ARGUMENT; } - if (strlen(RMW_UXRCE_DEFAULT_PORT) <= MAX_PORT_LEN) { + if (strlen(RMW_UXRCE_DEFAULT_PORT) < MAX_PORT_LEN) { snprintf( init_options->impl->transport_params.agent_port, MAX_PORT_LEN, "%s", RMW_UXRCE_DEFAULT_PORT); diff --git a/rmw_microxrcedds_c/src/rmw_microros/init_options.c b/rmw_microxrcedds_c/src/rmw_microros/init_options.c index ef42c080..a26b65d7 100644 --- a/rmw_microxrcedds_c/src/rmw_microros/init_options.c +++ b/rmw_microxrcedds_c/src/rmw_microros/init_options.c @@ -97,7 +97,7 @@ rmw_ret_t rmw_uros_options_set_udp_address( return RMW_RET_INVALID_ARGUMENT; } - if (port != NULL && strlen(port) <= MAX_PORT_LEN) { + if (port != NULL && strlen(port) < MAX_PORT_LEN) { snprintf(rmw_options->impl->transport_params.agent_port, MAX_PORT_LEN, "%s", port); } else { RMW_UROS_TRACE_MESSAGE("default port configuration error")