You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
. /opt/ros/eloquent/setup.bash
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
ros2 run demo_nodes_py listener
Expected behavior
[INFO] [1583870956.099600]: hello world 1583870956.1 (on Shell C) [INFO] [listener]: I heard: [hello world 1583870955.1] (on Shell D)
Actual behavior
Shell A:
created 1to2 bridge for topic '/chatter' with ROS 1 type 'std_msgs/String' and ROS 2 type 'std_msgs/msg/String'
[INFO] [ros_bridge]: Passing message from ROS 1 std_msgs/String to ROS 2 std_msgs/msg/String (showing msg only once per type)
realloc(): invalid pointer
Shell D hears exactly one message.
Additional information
Backtrace:
created 2to1 bridge for topic '/rosout' with ROS 2 type 'rcl_interfaces/msg/Log' and ROS 1 type 'rosgraph_msgs/Log'
created 1to2 bridge for topic '/chatter' with ROS 1 type 'std_msgs/String' and ROS 2 type 'std_msgs/msg/String'
[INFO] [ros_bridge]: Passing message from ROS 1 std_msgs/String to ROS 2 std_msgs/msg/String (showing msg only once per type)
realloc(): invalid pointer
Thread 1 "dynamic_bridge" received signal SIGABRT, Aborted.
__GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:51
51 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
(gdb) bt
#0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:51
#1 0x00007fffefbf4801 in __GI_abort () at abort.c:79
#2 0x00007fffefc3d897 in __libc_message (action=action@entry=do_abort,
fmt=fmt@entry=0x7fffefd6ab9a "%s\n") at ../sysdeps/posix/libc_fatal.c:181
#3 0x00007fffefc4490a in malloc_printerr (
str=str@entry=0x7fffefd68efd "realloc(): invalid pointer") at malloc.c:5350
#4 0x00007fffefc4ceba in __GI___libc_realloc (oldmem=0x555555815070, bytes=9)
at malloc.c:3174
#5 0x00007fffee7d4432 in rosidl_generator_c__String__assignn ()
from /opt/ros/eloquent/lib/librosidl_generator_c.so
#6 0x00007fffe644cfa5 in rmw_cyclonedds_cpp::StringHelper<rosidl_typesupport_introspection_c__MessageMembers>::assign (field=0x555555815060, deser=...)
at ./include/rmw_cyclonedds_cpp/TypeSupport.hpp:86
#7 rmw_cyclonedds_cpp::deserialize_field<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > (call_new=false, deser=..., field=0x555555815060,
member=0x7fffe44477e0) at ./include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:579
#8 rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_c__MessageMembers>::deserializeROSmessage (this=0x5555557d3f50, deser=..., members=0x7fffe4446900,
ros_message=0x555555815050, call_new=false)
at ./include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:732
#9 0x00007fffe6469bc1 in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_c__MessageMembers>::deserializeROSmessage(cycdeser&, void*, std::function<void (cycdeser&)>) (this=0x5555557d3f50, deser=..., ros_message=ros_message@entry=0x555555815050,
prefix=...) at ./include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:907
#10 0x00007fffe6467c28 in serdata_rmw_to_sample (dcmn=<optimized out>,
sample=0x555555815050, bufptr=<optimized out>, buflim=<optimized out>)
at ./src/serdata.cpp:282
#11 0x00007fffe61c379b in ddsi_serdata_to_sample (buflim=0x0, bufptr=0x0,
sample=<optimized out>, d=<optimized out>)
---Type <return> to continue, or q <return> to quit---
rdata.h:199
#12 dds_rhc_take_w_qminv (cond=0x0, handle=<optimized out>, qminv=0, max_samples=1, info_seq=0x7fffffffb370, values=0x7fffffffb368, lock=<optimized out>, rhc=0x5555558118b0)
at ./src/core/ddsc/src/dds_rhc_default.c:2016
#13 dds_rhc_default_take (cond=0x0, handle=<optimized out>, mask=<optimized out>, max_samples=<optimized out>, info_seq=<optimized out>, values=<optimized out>,
lock=<optimized out>, rhc=0x5555558118b0) at ./src/core/ddsc/src/dds_rhc_default.c:2640
#14 dds_rhc_default_take_wrap (rhc=0x5555558118b0, lock=<optimized out>, values=0x7fffffffb368, info_seq=0x7fffffffb370, max_samples=1, mask=<optimized out>,
handle=<optimized out>, cond=0x0) at ./src/core/ddsc/src/dds_rhc_default.c:379
#15 0x00007fffe61cc87e in dds_rhc_take (cond=<optimized out>, handle=0, mask=128, max_samples=1, info_seq=0x7fffffffb370, values=0x7fffffffb368, lock=true, rhc=<optimized out>)
at ./src/core/ddsc/include/dds/ddsc/dds_rhc.h:83
#16 dds_read_impl (take=take@entry=true, reader_or_condition=<optimized out>, buf=buf@entry=0x7fffffffb368, bufsz=<optimized out>, maxs=1, si=0x7fffffffb370, mask=128, hand=0,
lock=true, only_reader=false) at ./src/core/ddsc/src/dds_read.c:120
#17 0x00007fffe61cce80 in dds_take (rd_or_cnd=<optimized out>, buf=buf@entry=0x7fffffffb368, si=si@entry=0x7fffffffb370, bufsz=bufsz@entry=1, maxs=<optimized out>, maxs@entry=1)
at ./src/core/ddsc/src/dds_read.c:331
#18 0x00007fffe6438013 in rmw_take_int (subscription=<optimized out>, ros_message=<optimized out>, taken=0x7fffffffb42f, message_info=0x7fffffffc8e0) at ./src/rmw_node.cpp:1610
#19 0x00007ffff7860748 in rcl_take () from /opt/ros/eloquent/lib/librcl.so
#20 0x00007ffff7b0fb1a in rclcpp::executor::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/eloquent/lib/librclcpp.so
#21 0x00007ffff7b11045 in rclcpp::executor::Executor::execute_any_executable(rclcpp::executor::AnyExecutable&) () from /opt/ros/eloquent/lib/librclcpp.so
#22 0x00007ffff7b13d35 in rclcpp::executor::Executor::spin_once(std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/eloquent/lib/librclcpp.so
#23 0x00007ffff7b0f351 in rclcpp::executor::Executor::spin_node_once_nanoseconds(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/eloquent/lib/librclcpp.so
#24 0x000055555557c165 in rclcpp::executor::Executor::spin_node_once<rclcpp::Node, long, std::ratio<1l, 1000l> > (this=0x7fffffffdc60,
node=std::shared_ptr<rclcpp::Node> (use count 7, weak count 1) = {...}, timeout=...) at /opt/ros/eloquent/include/rclcpp/executor.hpp:178
#25 0x0000555555573e93 in main (argc=1, argv=0x7fffffffde68) at /home/knickels/code/ros1_bridge_ws/src/ros1_bridge/src/dynamic_bridge.cpp:784
(gdb)
The text was updated successfully, but these errors were encountered:
Operating System:
Description: Ubuntu 18.04.4 LTS
(same result in docker and native)
Installation type:
melodic binaries, eloquent binaries, ros1_bridge source
Version or commit hash:
On eloquent branch of ros1_bridge:
± git rev-parse HEAD
60f903c
DDS implementation:
rmw_cyclonedds_cpp (works with Fast-RTPS)
Client library (if applicable):
rclpy, rospy
Steps to reproduce issue
Shell A:
Shell B:
Shell C:
Shell D:
Expected behavior
[INFO] [1583870956.099600]: hello world 1583870956.1
(on Shell C)[INFO] [listener]: I heard: [hello world 1583870955.1]
(on Shell D)Actual behavior
Shell A:
Shell D hears exactly one message.
Additional information
Backtrace:
The text was updated successfully, but these errors were encountered: