Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_DDS: use memset to initialise variable size array #28596

Merged

Conversation

srmainwaring
Copy link
Contributor

@srmainwaring srmainwaring commented Nov 12, 2024

The macOS version of clangdoes not support initialisation of variable length arrays. Use memset instead.

System:
MacBook Pro M1
macOS Sonoma 14.5
Xcode 15.3 (15E204a)

Compiler details from ./waf configure

% ./waf configure --board sitl --enable-dds --debug
Setting top to                           : /Users/rhys/Code/ros2/rolling/ros2-ardupilot/src/ardupilot 
Setting out to                           : /Users/rhys/Code/ros2/rolling/ros2-ardupilot/src/ardupilot/build 
Autoconfiguration                        : enabled 
Checking for program 'python'            : /Users/rhys/.venv/ros2-rolling/bin/python3 
Checking for python version >= 3.6.9     : 3.12.7 
Setting board to                         : sitl 
Using toolchain                          : native 
Checking for 'g++' (C++ compiler)        : not found 
Checking for 'clang++' (C++ compiler)    : /usr/bin/clang++ 
Checking for 'gcc' (C compiler)          : not found 
Checking for 'clang' (C compiler)        : /usr/bin/clang 
Checking for c flags '-MMD'              : yes 
Checking for cxx flags '-MMD'            : yes 
CXX Compiler                             : clang++ 15.0.0 
Checking for feenableexcept              : no 
Disabling SLP for clang++
Enabling -Werror                         : no 
Checking for program 'microxrceddsgen'   : /Users/rhys/Code/ros2/rolling/ros2-ardupilot/src/microxrcedds_gen/scripts/microxrceddsgen 
Enabled OpenDroneID                      : no 
Enabled firmware ID checking             : no 
GPS Debug Logging                        : no 
Enabled custom controller                : yes 
Checking for HAVE_CMATH_ISFINITE         : yes 
Checking for HAVE_CMATH_ISINF            : yes 
Checking for HAVE_CMATH_ISNAN            : yes 
Checking for NEED_CMATH_ISFINITE_STD_NAMESPACE : yes 
Checking for NEED_CMATH_ISINF_STD_NAMESPACE    : yes 
Checking for NEED_CMATH_ISNAN_STD_NAMESPACE    : yes 
Checking for header endian.h                   : not found 
Checking for header byteswap.h                 : not found 
Checking for HAVE_MEMRCHR                      : no 
Configured VSCode Intellisense:                : no 
DC_DSDL compiler in                            : /Users/rhys/Code/ros2/rolling/ros2-ardupilot/src/ardupilot/modules/DroneCAN/dronecan_dsdlc 
Source is git repository                       : yes 
Update submodules                              : yes 
Checking for program 'git'                     : /opt/homebrew/bin/git 
Checking for program 'size'                    : /usr/bin/size 
Benchmarks                                     : disabled 
Unit tests                                     : enabled 
Scripting                                      : maybe 
Scripting runtime checks                       : enabled 
Debug build                                    : enabled 
Coverage build                                 : disabled 
Force 32-bit build                             : disabled 
Checking for program 'rsync'                   : /opt/homebrew/bin/rsync 
Removing target_list file /Users/rhys/Code/ros2/rolling/ros2-ardupilot/src/ardupilot/build/sitl/target_list
'configure' finished successfully (2.052s)

uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
uint8_t reply_buffer[reply_size] {};
const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
uint8_t reply_buffer[reply_size];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it any initialisation of variable length arrays, or this specific syntax? Can you do the following instead?

Suggested change
uint8_t reply_buffer[reply_size];
uint8_t reply_buffer[reply_size] = { 0 };

Copy link
Contributor Author

@srmainwaring srmainwaring Nov 12, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, the suggested change fails to compile. I've added more detail on the system and compiler version in the PR header.

../../libraries/AP_DDS/AP_DDS_Client.cpp:967:30: fatal error: variable-sized object may not be initialized
        uint8_t reply_buffer[reply_size] = { 0 };
                             ^~~~~~~~~~
2 warnings and 1 error generated.

@Ryanf55
Copy link
Collaborator

Ryanf55 commented Nov 12, 2024

Introduced by #28298

@peterbarker peterbarker merged commit 2bd4e15 into ArduPilot:master Nov 12, 2024
99 checks passed
@srmainwaring srmainwaring deleted the prs/pr-dds-memset-reply-buf branch November 13, 2024 18:13
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: Done
Development

Successfully merging this pull request may close these issues.

4 participants