=================================================================
==12915==ERROR: AddressSanitizer: attempting free on address which was not malloc()-ed: 0x63100003c838 in thread T9
#0 0x7f70018b4537 in __interceptor_free ../../../../src/libsanitizer/asan/asan_malloc_linux.cpp:127
**#1 0x7f6ffad9a681 in eprosima::fastrtps::rtps::SerializedPayload_t::empty() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/include/fastdds/rtps/common/SerializedPayload.h:158
#2 0x7f6ffad9a681 in eprosima::fastrtps::rtps::SerializedPayload_t::~SerializedPayload_t() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/include/fastdds/rtps/common/SerializedPayload.h:92
#3 0x7f6ffad9a681 in eprosima::fastrtps::rtps::CacheChange_t::~CacheChange_t() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/include/fastdds/rtps/common/CacheChange.h:184
#4 0x7f6ffad9a681 in eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/messages/MessageReceiver.cpp:1071**
#5 0x7f6ffad9e55f in eprosima::fastrtps::rtps::MessageReceiver::processCDRMsg(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::CDRMessage_t*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/messages/MessageReceiver.cpp:459
#6 0x7f6ffada5e8d in eprosima::fastrtps::rtps::ReceiverResource::OnDataReceived(unsigned char const*, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::Locator_t const&) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:134
#7 0x7f6ffae81f29 in eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:70
#8 0x7f6ffae82783 in void std::__invoke_impl<void, void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t>(std::__invoke_memfun_deref, void (eprosima::fastdds::rtps::UDPChannelResource::*&&)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*&&, eprosima::fastrtps::rtps::Locator_t&&) /usr/include/c++/11/bits/invoke.h:74
#9 0x7f6ffae82783 in std::__invoke_result<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t>::type std::__invoke<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t>(void (eprosima::fastdds::rtps::UDPChannelResource::*&&)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*&&, eprosima::fastrtps::rtps::Locator_t&&) /usr/include/c++/11/bits/invoke.h:96
#10 0x7f6ffae82783 in void std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul>(std::_Index_tuple<0ul, 1ul, 2ul>) /usr/include/c++/11/bits/std_thread.h:259
#11 0x7f6ffae82783 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator()() /usr/include/c++/11/bits/std_thread.h:266
#12 0x7f6ffae82783 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run() /usr/include/c++/11/bits/std_thread.h:211
#13 0x7f70006dc252 (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc252)
#14 0x7f7000294ac2 in start_thread nptl/pthread_create.c:442
#15 0x7f700032665f (/lib/x86_64-linux-gnu/libc.so.6+0x12665f)
0x63100003c838 is located 56 bytes inside of 65500-byte region [0x63100003c800,0x63100004c7dc)
allocated by thread T0 here:
#0 0x7f70018b4887 in __interceptor_malloc ../../../../src/libsanitizer/asan/asan_malloc_linux.cpp:145
#1 0x7f6ffae813e7 in eprosima::fastrtps::rtps::CDRMessage_t::CDRMessage_t(unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/include/fastdds/rtps/common/CDRMessage_t.h:79
#2 0x7f6ffae813e7 in eprosima::fastdds::rtps::ChannelResource::ChannelResource(unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/ChannelResource.cpp:45
#3 0x7f6ffae8244d 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:40
#4 0x7f6ffaeb1fa8 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:234
#5 0x7f6ffaeb2dc4 in eprosima::fastdds::rtps::UDPTransportInterface::OpenAndBindInputSockets(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, bool, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:207
#6 0x7f6ffae9e857 in eprosima::fastdds::rtps::UDPv4Transport::OpenInputChannel(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPv4Transport.cpp:328
#7 0x7f6ffada603c in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource(eprosima::fastdds::rtps::TransportInterface&, eprosima::fastrtps::rtps::Locator_t const&, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:45
#8 0x7f6ffada4bc3 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) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/network/NetworkFactory.cpp:100
#9 0x7f6ffadab5c9 in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources(eprosima::fastdds::rtps::LocatorList&, bool, bool) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1700
#10 0x7f6ffadb2796 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:358
#11 0x7f6ffadb3322 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:450
#12 0x7f6ffadc0fcc in eprosima::fastrtps::rtps::RTPSDomainImpl::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:199
#13 0x7f6ffae60dbf in eprosima::fastdds::dds::DomainParticipantImpl::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantImpl.cpp:277
#14 0x7f6ffb0d116f in eprosima::fastdds::statistics::dds::DomainParticipantImpl::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/statistics/fastdds/domain/DomainParticipantImpl.cpp:253
#15 0x7f6ffae722bb in eprosima::fastdds::dds::DomainParticipant::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:110
#16 0x7f6ffae722bb in eprosima::fastdds::dds::DomainParticipant::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:102
#17 0x7f6ffae55563 in eprosima::fastdds::dds::DomainParticipantFactory::create_participant(unsigned int, eprosima::fastdds::dds::DomainParticipantQos const&, eprosima::fastdds::dds::DomainParticipantListener*, eprosima::fastdds::dds::StatusMask const&) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantFactory.cpp:189
#18 0x7f6ffd65b292 in __create_participant /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:102
#19 0x7f6ffd65cdef in rmw_fastrtps_shared_cpp::create_participant(char const*, unsigned long, rmw_security_options_s const*, rmw_discovery_options_s const*, char const*, rmw_dds_common::Context*) /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:370
#20 0x7f70004a50cd in init_context_impl /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:76
#21 0x7f70004a597f in rmw_fastrtps_cpp::increment_context_impl_ref_count(rmw_context_s*) /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:200
#22 0x7f70004b63d3 in rmw_create_node /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_node.cpp:60
#23 0x7f70022f4496 in rcl_node_init /home/suwan/ros2_iron/src/ros2/rcl/rcl/src/rcl/node.c:258
Thread T9 created by T0 here:
#0 0x7f7001858685 in __interceptor_pthread_create ../../../../src/libsanitizer/asan/asan_interceptors.cpp:216
#1 0x7f70006dc328 in std::thread::_M_start_thread(std::unique_ptr<std::thread::_State, std::default_delete<std::thread::_State> >, void (*)()) (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc328)
#2 0x7f6ffaeb1fa8 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:234
#3 0x7f6ffaeb2dc4 in eprosima::fastdds::rtps::UDPTransportInterface::OpenAndBindInputSockets(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, bool, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPTransportInterface.cpp:207
#4 0x7f6ffae9e857 in eprosima::fastdds::rtps::UDPv4Transport::OpenInputChannel(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPv4Transport.cpp:328
#5 0x7f6ffada603c in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource(eprosima::fastdds::rtps::TransportInterface&, eprosima::fastrtps::rtps::Locator_t const&, unsigned int) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:45
#6 0x7f6ffada4bc3 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) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/network/NetworkFactory.cpp:100
#7 0x7f6ffadab5c9 in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources(eprosima::fastdds::rtps::LocatorList&, bool, bool) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1700
#8 0x7f6ffadb2796 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:358
#9 0x7f6ffadb3322 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*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:450
#10 0x7f6ffadc0fcc in eprosima::fastrtps::rtps::RTPSDomainImpl::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:199
#11 0x7f6ffae60dbf in eprosima::fastdds::dds::DomainParticipantImpl::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantImpl.cpp:277
#12 0x7f6ffb0d116f in eprosima::fastdds::statistics::dds::DomainParticipantImpl::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/statistics/fastdds/domain/DomainParticipantImpl.cpp:253
#13 0x7f6ffae722bb in eprosima::fastdds::dds::DomainParticipant::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:110
#14 0x7f6ffae722bb in eprosima::fastdds::dds::DomainParticipant::enable() /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:102
#15 0x7f6ffae55563 in eprosima::fastdds::dds::DomainParticipantFactory::create_participant(unsigned int, eprosima::fastdds::dds::DomainParticipantQos const&, eprosima::fastdds::dds::DomainParticipantListener*, eprosima::fastdds::dds::StatusMask const&) /home/suwan/ros2_iron/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantFactory.cpp:189
#16 0x7f6ffd65b292 in __create_participant /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:102
#17 0x7f6ffd65cdef in rmw_fastrtps_shared_cpp::create_participant(char const*, unsigned long, rmw_security_options_s const*, rmw_discovery_options_s const*, char const*, rmw_dds_common::Context*) /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:370
#18 0x7f70004a50cd in init_context_impl /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:76
#19 0x7f70004a597f in rmw_fastrtps_cpp::increment_context_impl_ref_count(rmw_context_s*) /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:200
#20 0x7f70004b63d3 in rmw_create_node /home/suwan/ros2_iron/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_node.cpp:60
#21 0x7f70022f4496 in rcl_node_init /home/suwan/ros2_iron/src/ros2/rcl/rcl/src/rcl/node.c:258
SUMMARY: AddressSanitizer: bad-free ../../../../src/libsanitizer/asan/asan_malloc_linux.cpp:127 in __interceptor_free
==12915==ABORTING
// 916 line
bool MessageReceiver::proc_Submsg_DataFrag(
CDRMessage_t* msg,
SubmessageHeader_t* smh,
bool was_decoded) const
{
....
uint32_t inlineQosSize = 0;
if (inlineQosFlag)
{
if (!ParameterList::updateCacheChangeFromInlineQos(ch, msg, inlineQosSize))
{
EPROSIMA_LOG_INFO(RTPS_MSG_IN, IDSTRING "SubMessage Data ERROR, Inline Qos ParameterList error");
return false;
}
ch.inline_qos.data = &msg->buffer[msg->pos - inlineQosSize];
ch.inline_qos.max_size = inlineQosSize;
ch.inline_qos.length = inlineQosSize;
ch.inline_qos.encapsulation = endiannessFlag ? PL_CDR_LE : PL_CDR_BE;
ch.inline_qos.pos = 0;
}
uint32_t payload_size;
payload_size = smh->submessageLength - (RTPSMESSAGE_DATA_EXTRA_INLINEQOS_SIZE + octetsToInlineQos + inlineQosSize);
if (!keyFlag)
{
uint32_t next_pos = msg->pos + payload_size;
if (msg->length >= next_pos && payload_size > 0) //pass this if()
{
ch.kind = ALIVE;
ch.serializedPayload.data = &msg->buffer[msg->pos];
ch.serializedPayload.length = payload_size;
ch.serializedPayload.max_size = payload_size;
ch.setFragmentSize(fragmentSize);
msg->pos = next_pos;
}
**else
{
EPROSIMA_LOG_WARNING(RTPS_MSG_IN, IDSTRING "Serialized Payload value invalid or larger than maximum allowed size "
"(" << payload_size << "/" << (msg->length - msg->pos) << ")");
return false; // [root cause] after false -> destructor destructor
}**
}
else if (keyFlag)
{
/* XXX TODO
Endianness_t previous_endian = msg->msg_endian;
if (ch->serializedPayload.encapsulation == PL_CDR_BE)
msg->msg_endian = BIGEND;
else if (ch->serializedPayload.encapsulation == PL_CDR_LE)
msg->msg_endian = LITTLEEND;
else
{
EPROSIMA_LOG_ERROR(RTPS_MSG_IN, IDSTRING"Bad encapsulation for KeyHash and status parameter list");
return false;
}
//uint32_t param_size;
if (ParameterList::readParameterListfromCDRMsg(msg, &m_ParamList, ch, false) <= 0)
{
EPROSIMA_LOG_INFO(RTPS_MSG_IN, IDSTRING"SubMessage Data ERROR, keyFlag ParameterList");
return false;
}
msg->msg_endian = previous_endian;
*/
}
// Set sourcetimestamp
if (have_timestamp_)
{
ch.sourceTimestamp = timestamp_;
}
EPROSIMA_LOG_INFO(RTPS_MSG_IN, IDSTRING "from Writer " << ch.writerGUID << "; possible RTPSReader entities: " <<
associated_readers_.size());
process_data_fragment_message_function_(readerID, ch, sampleSize, fragmentStartingNum, fragmentsInSubmessage,
was_decoded);
ch.serializedPayload.data = nullptr;
ch.inline_qos.data = nullptr;
EPROSIMA_LOG_INFO(RTPS_MSG_IN, IDSTRING "Sub Message DATA_FRAG processed");
return true;
}
───────────────────────────────────────────────────────────────────────────────────[ DISASM / x86-64 / set emulate on ]────────────────────────────────────────────────────────────────────────────────────
0x7ffff599a65f <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+527> test rdi, rdi
0x7ffff599a662 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+530> je eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+545 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+545>
↓
0x7ffff599a671 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+545> mov rdi, qword ptr [rbp - 0x258]
0x7ffff599a678 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+552> test rdi, rdi
0x7ffff599a67b <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+555> je eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+562 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+562>
► 0x7ffff599a67d <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557> call free@plt <free@plt>
ptr: 0x5555556819c8 ◂— 0x100000000
0x7ffff599a682 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+562> mov rdi, qword ptr [rbp - 0x270]
0x7ffff599a689 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+569> test rdi, rdi
0x7ffff599a68c <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+572> je eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+587 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+587>
0x7ffff599a68e <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+574> call free@plt <free@plt>
0x7ffff599a693 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+579> jmp eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+587 <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+587>
─────────────────────────────────────────────────────────────────────────────────────────────[ SOURCE (CODE) ]─────────────────────────────────────────────────────────────────────────────────────────────
In file: /home/suwan/ros2_iron/src/eProsima/Fast-DDS/include/fastdds/rtps/common/SerializedPayload.h
153 void empty()
154 {
155 length = 0;
156 encapsulation = CDR_BE;
157 max_size = 0;
► 158 if (data != nullptr)
159 {
160 free(data);*
161 }
162 data = nullptr;
163 }
─────────────────────────────────────────────────────────────────────────────────────────────────[ STACK ]─────────────────────────────────────────────────────────────────────────────────────────────────
00:0000│ rsp 0x7fffed7f8530 —▸ 0x7fffed7f8994 ◂— 0x4400000016
01:0008│ 0x7fffed7f8538 —▸ 0x7ffff7fd8dae (_dl_runtime_resolve_xsavec+126) ◂— mov r11, rax
02:0010│ 0x7fffed7f8540 —▸ 0x7ffff599e52b (eprosima::fastrtps::rtps::MessageReceiver::processCDRMsg(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::CDRMessage_t*)+1979) ◂— mov rdx, qword ptr [rbp - 0x1ec]
03:0018│ 0x7fffed7f8548 ◂— 0x1
04:0020│ 0x7fffed7f8550 —▸ 0x7fffed7f8994 ◂— 0x4400000016
05:0028│ 0x7fffed7f8558 —▸ 0x7fffed7f8bd0 —▸ 0x555555681990 ◂— 0xca010253505452
06:0030│ 0x7fffed7f8560 —▸ 0x555555660f90 —▸ 0x7ffff5faf4d8 (vtable for eprosima::fastrtps::rtps::MessageReceiver+16) —▸ 0x7ffff59952e0 (eprosima::fastrtps::rtps::MessageReceiver::~MessageReceiver()) ◂— endbr64
07:0038│ 0x7fffed7f8568 ◂— 0x0
───────────────────────────────────────────────────────────────────────────────────────────────[ BACKTRACE ]───────────────────────────────────────────────────────────────────────────────────────────────
► 0 0x7ffff599a67d eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557
1 0x7ffff599a67d eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557
2 0x7ffff599a67d eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557
3 0x7ffff599a67d eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557
4 0x7ffff599e560 eprosima::fastrtps::rtps::MessageReceiver::processCDRMsg(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::CDRMessage_t*)+2032
5 0x7ffff59a5e8e eprosima::fastrtps::rtps::ReceiverResource::OnDataReceived(unsigned char const*, unsigned int, eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastrtps::rtps::Locator_t const&)+206
6 0x7ffff5a81f2a eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)+154
7 0x7ffff5a82784 std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run()+84
──────────────────────────────────────────────────────────────────────────────────────────[ THREADS (13 TOTAL) ]───────────────────────────────────────────────────────────────────────────────────────────
► 10 "listener" stopped: 0x7ffff599a67d <eprosima::fastrtps::rtps::MessageReceiver::proc_Submsg_DataFrag(eprosima::fastrtps::rtps::CDRMessage_t*, eprosima::fastrtps::rtps::SubmessageHeader_t*) const+557>
1 "listener" stopped: 0x7ffff7491117 <__futex_abstimed_wait_cancelable64+231>
2 "listener-ust" stopped: 0x7ffff752764f <recvmsg+95>
3 "listener-ust" stopped: 0x7ffff751e69d <syscall+29>
Not showing 9 thread(s). Use set context-max-threads <number of threads> to change this.
1. Summary
Inline_qos, SerializedPayload
member of objectch
will attempt to release memory without initialization, resulting in a 'bad-free' error.2. Details
ASAN Report
Analysis Code With GDB
1. The code that causes
2. Run the destructor after the termination of the proc_Submsg_DataFrag function.
The results of the analysis
3. PoC
4. Impact
5. Recommendations
Inline_qos
andserializedPayload
members of theCacheChange_t
objectch
need to be initialized.