Closed mauropasse closed 2 years ago
@mauropasse @alsora Would you mind checking if this can be incorporated into #619?
Hi @MiguelCompany. Good thing, https://github.com/ros2/rmw_fastrtps/pull/619 already adds listener callbacks associated with those new events (so this PR wouldn't be needed). Bad thing, it segs fault when adding listener callbacks. This simple program reproduces the issue
#include <memory>
#include <iostream>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<rclcpp::Node>("my_node");
auto pub = node->create_publisher<std_msgs::msg::String>("topic", 10);
auto sub = node->create_subscription<std_msgs::msg::String>(
"topic", 10, [](std_msgs::msg::String::UniquePtr msg) {});
// This line provokes a seg fault when later pub->publish(message) is called:
sub->set_on_new_message_callback([](size_t n) {
std::cout << "New message callback" << std::endl;});
auto message = std_msgs::msg::String();
message.data = "Hello, world!";
pub->publish(message);
std::this_thread::sleep_for(std::chrono::seconds(2));
rclcpp::shutdown();
return 0;
}
Calling set_on_new_message_callback
and then pub->publish(message)
has a seg fault:
#0 0x00007ffff630e8ab in eprosima::fastcdr::FastBuffer::reserve (this=0x0, size=22) at eProsima/Fast-CDR/src/cpp/FastBuffer.cpp:54
#1 0x00007ffff6e2d6f0 in rmw_fastrtps_shared_cpp::TypeSupport::deserialize (this=0x55555595aee0, payload=0x55555596ed90, data=0x55555596f270)
at ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/TypeSupport_impl.cpp:108
#2 0x00007ffff66d29bd in eprosima::fastdds::dds::detail::SampleLoanManager::get_loan (this=0x55555596ecc0, change=change@entry=0x555555970390,
sample=@0x7fffffff1c38: 0x555555969bd0) at /usr/include/c++/11/bits/shared_ptr_base.h:1295
#3 0x00007ffff66c7613 in eprosima::fastdds::dds::detail::ReadTakeCommand::deserialize_sample (change=0x555555970390, this=0x7fffffff1d10)
at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl/ReadTakeCommand.hpp:326
#4 eprosima::fastdds::dds::detail::ReadTakeCommand::deserialize_sample (change=0x555555970390, this=0x7fffffff1d10)
at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl/ReadTakeCommand.hpp:313
#5 eprosima::fastdds::dds::detail::ReadTakeCommand::add_sample (deserialization_error=<synthetic pointer>: false, change=0x555555970390,
this=0x7fffffff1d10) at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl/ReadTakeCommand.hpp:290
#6 eprosima::fastdds::dds::detail::ReadTakeCommand::add_instance (this=0x7fffffff1d10, take_samples=<optimized out>)
at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl/ReadTakeCommand.hpp:148
#7 0x00007ffff66c7eda in eprosima::fastdds::dds::DataReaderImpl::read_or_take (this=0x555555969bd0, data_values=..., sample_infos=...,
max_samples=<optimized out>, handle=..., sample_states=2, view_states=3, instance_states=7, exact_instance=false, single_instance=<optimized out>,
should_take=false) at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl.cpp:495
#8 0x00007ffff66c7f7a in eprosima::fastdds::dds::DataReaderImpl::read (this=<optimized out>, data_values=..., sample_infos=...,
max_samples=<optimized out>, sample_states=<optimized out>, view_states=<optimized out>, instance_states=7)
at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl.cpp:508
#9 0x00007ffff6da9d86 in SubListener::get_unread_messages (this=0x5555559694f0)
at ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/custom_subscriber_info.cpp:241
#10 0x00007ffff6da9ee8 in SubListener::on_data_available (this=0x5555559694f0)
at ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/custom_subscriber_info.cpp:266
#11 0x00007ffff66cd5b9 in eprosima::fastdds::dds::DataReaderImpl::InnerDataReaderListener::onNewCacheChangeAdded (change_in=<optimized out>,
this=0x55555596d108) at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl.cpp:830
#12 eprosima::fastdds::dds::DataReaderImpl::InnerDataReaderListener::onNewCacheChangeAdded (this=0x55555596d108, change_in=<optimized out>)
at eProsima/Fast-DDS/src/cpp/fastdds/subscriber/DataReaderImpl.cpp:809
#13 0x00007ffff663677d in eprosima::fastrtps::rtps::StatefulReader::NotifyChanges (this=this@entry=0x55555596f810, prox=<optimized out>)
at eProsima/Fast-DDS/src/cpp/rtps/reader/StatefulReader.cpp:908
#14 0x00007ffff6636994 in eprosima::fastrtps::rtps::StatefulReader::change_received (this=this@entry=0x55555596f810, a_change=0x555555970390,
prox=<optimized out>) at eProsima/Fast-DDS/src/cpp/rtps/reader/StatefulReader.cpp:877
#15 0x00007ffff663cda5 in eprosima::fastrtps::rtps::StatefulReader::processDataMsg (this=0x55555596f810, change=0x55555595f990)
at eProsima/Fast-DDS/src/cpp/rtps/reader/StatefulReader.cpp:495
#16 0x00007ffff65fd84a in eprosima::fastrtps::rtps::StatefulWriter::deliver_sample_to_intraprocesses (this=0x55555595ea60, change=0x55555595f990)
at eProsima/Fast-DDS/src/cpp/rtps/writer/StatefulWriter.cpp:648
#17 0x00007ffff6602ff5 in eprosima::fastrtps::rtps::StatefulWriter::deliver_sample_nts (this=0x55555595ea60, cache_change=0x55555595f990, group=...,
locator_selector=..., max_blocking_time=...) at eProsima/Fast-DDS/src/cpp/rtps/writer/StatefulWriter.cpp:2025
#18 0x00007ffff6896065 in eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::add_new_sample_impl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode> (max_blocking_time=..., change=<optimized out>,
writer=<optimized out>, this=<optimized out>) at eProsima/Fast-DDS/src/cpp/rtps/flowcontrol/FlowControllerImpl.hpp:1147
#19 eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::add_new_sample (this=0x55555575b440, writer=0x55555595ea60, change=0x55555595f990, max_blocking_time=...)
at eProsima/Fast-DDS/src/cpp/rtps/flowcontrol/FlowControllerImpl.hpp:993
#20 0x00007ffff65fed20 in eprosima::fastrtps::rtps::StatefulWriter::unsent_change_added_to_history (this=0x55555595ea60, change=<optimized out>,
max_blocking_time=...) at eProsima/Fast-DDS/src/cpp/rtps/writer/StatefulWriter.cpp:430
#21 0x00007ffff661c17d in eprosima::fastrtps::rtps::WriterHistory::add_change_ (this=this@entry=0x555555965070, a_change=<optimized out>,
a_change@entry=0x55555595f990, wparams=..., max_blocking_time=...) at eProsima/Fast-DDS/src/cpp/rtps/history/WriterHistory.cpp:117
#22 0x00007ffff66abca4 in eprosima::fastrtps::PublisherHistory::add_pub_change (this=this@entry=0x555555965070, change=<optimized out>,
change@entry=0x55555595f990, wparams=..., lock=..., max_blocking_time=...)
at eProsima/Fast-DDS/src/cpp/fastrtps_deprecated/publisher/PublisherHistory.cpp:220
#23 0x00007ffff66d97e2 in eprosima::fastdds::dds::DataWriterImpl::perform_create_new_change (this=0x555555964c20, change_kind=<optimized out>,
data=0x7fffffff2df0, wparams=..., handle=...) at eProsima/Fast-DDS/src/cpp/fastdds/publisher/DataWriterImpl.cpp:726
#24 0x00007ffff66d9d8e in eprosima::fastdds::dds::DataWriterImpl::create_new_change_with_params (wparams=..., data=0x7fffffff2df0,
changeKind=eprosima::fastrtps::rtps::ALIVE, this=0x555555964c20) at eProsima/Fast-DDS/src/cpp/fastdds/publisher/DataWriterImpl.cpp:793
#25 eprosima::fastdds::dds::DataWriterImpl::create_new_change_with_params (this=0x555555964c20, changeKind=eprosima::fastrtps::rtps::ALIVE,
data=0x7fffffff2df0, wparams=...) at eProsima/Fast-DDS/src/cpp/fastdds/publisher/DataWriterImpl.cpp:772
#26 0x00007ffff66d9e70 in eprosima::fastdds::dds::DataWriterImpl::create_new_change (this=<optimized out>,
changeKind=changeKind@entry=eprosima::fastrtps::rtps::ALIVE, data=<optimized out>)
at eProsima/Fast-DDS/src/cpp/fastdds/publisher/DataWriterImpl.cpp:656
#27 0x00007ffff66d9ea9 in eprosima::fastdds::dds::DataWriterImpl::write (this=<optimized out>, data=<optimized out>)
at eProsima/Fast-DDS/src/cpp/fastdds/publisher/DataWriterImpl.cpp:491
#28 0x00007ffff6dff42c in rmw_fastrtps_shared_cpp::__rmw_publish (identifier=0x7ffff6efcfe2 "rmw_fastrtps_cpp", publisher=0x55555595ba90,
ros_message=0x7fffffff3480, allocation=0x0) at ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_publish.cpp:61
#29 0x00007ffff6edebe7 in rmw_publish (publisher=0x55555595ba90, ros_message=0x7fffffff3480, allocation=0x0)
at ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_publish.cpp:34
#30 0x00007ffff7197a80 in rmw_publish (v3=0x55555595ba90, v2=0x7fffffff3480, v1=0x0)
at ros2/rmw_implementation/rmw_implementation/src/functions.cpp:317
#31 0x00007ffff76a8b73 in rcl_publish (publisher=0x55555595b990, ros_message=0x7fffffff3480, allocation=0x0)
at ros2/rcl/rcl/src/rcl/publisher.c:249
#32 0x00005555555d6830 in rclcpp::Publisher<std_msgs::msg::String_<std::allocator<void> >, std::allocator<void> >::do_inter_process_publish (
this=0x55555595c650, msg=...) at /root/my_ws/install/include/rclcpp/rclcpp/publisher.hpp:453
#33 0x00005555555d3ffa in rclcpp::Publisher<std_msgs::msg::String_<std::allocator<void> >, std::allocator<void> >::publish<std_msgs::msg::String_<std::allocator<void> > > (this=0x55555595c650, msg=...) at /root/my_ws/install/include/rclcpp/rclcpp/publisher.hpp:297
#34 0x00005555555c7f43 in main (argc=1, argv=0x7fffffff3778) at ros2/examples/rclcpp/composition/minimal_composition/src/composed.cpp:26
Hi @mauropasse,
Thanks for the reproducer and stack trace. I have just pushed a commit that fixes the issue.
@jsantiago-eProsima I checked your new commits and all seems to work fine now, thanks!
The recently merged PR https://github.com/ros2/rmw_fastrtps/pull/583 added support for missing events:
This PR adds listener callbacks associated with those new events.
Also a bug is fixed in which setting a callback for some event type, would override the any previous other callback set (there was a single callback for listener). Now we have multiple callbacks for the different listener event types.
@alsora FYI