Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -23,15 +23,14 @@ 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
git clone -b jazzy https://github.com/ros2/rmw src/rmw
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
Expand Down
2 changes: 1 addition & 1 deletion rmw_microxrcedds_c/include/rmw_microros/rmw_microros.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion rmw_microxrcedds_c/src/rmw_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion rmw_microxrcedds_c/src/rmw_microros/init_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand Down