Closed MengNan-Li closed 5 years ago
The RTPS_WRITER error seems like a problem in the FastRTPS layer or a memory leak. I have a few questions.
top -o %MEM
when this occurs to see if anything is using a lot of memory?This happened when the robot is idle.
So. we don't care about the RTPS_WRITER error for now. But time-stamped bias problems have a great impact on coordinate system transformation. This problem also exists in the gazebo simulation(Steps). As follows. ros2 launch nav2_bringup nav2_bringup_launch.py use_sim_time:=True autostart:=True map:=××
The robot moves a little from time to time.
It looks like the local costmap has stopped receiving clock messages; time has stopped advancing for that node. Neither node is receiving updated transforms.
This seems like a communication problem to me. We seem to run into those a lot with FastRTPS. That's why I was concerned about the RTPS_WRITER error.
Here are two things to try:
RMW_IMPLEMENTATION=rmw_opensplice_cpp
variable. We've found that communication in Opensplice is sometimes more reliable.@crdelsey Hi, I know the ROS_DOMAIN_ID variable. When i change the DDS to OpenSplice, the problem is gone. But, The Rviz2 tf error still exists, which does not affect the use of Navigation2.
Now, both gazebo and real robot can use navigation for motion planning. During the testing of the navigation2, I found several other issues. Such as amcl's particlecloud display in Rviz2, avoiding etc. Now, i close this issue and ask other questions separately.
Think you very much.
I'm glad to hear Opensplice fixed the problem for you. We still have problems with all the different DDS implementations, but usually, each one has different problems. We plan to help fix some of these problems before the eloquent release.
But, The Rviz2 tf error still exists, which does not affect the use of Navigation2.
I suspect that RViz still needs to enable message filters for some messages. I believe the problem here is that it tries to process laser scan data, but the transform data is not available yet. We had the same problem in the navigation stack until we were able to use message filters in ROS 2.
Bug report
Required Info:
Steps to reproduce issue
Expected behavior
The position of the robot will not be lost because of amcl and odom.
Actual behavior
The robot pose will lose along with moving the robot.
Additional information
[amcl-3] [INFO] [amcl]: Setting pose (1562641158.917216): 11.976 12.320 -0.459 [amcl-3] [WARN] [amcl]: Failed to transform initial pose in time (Lookup would require extrapolation into the future. Requested time 1562641158.91716 but the latest data is at time 1562641158.87269, when looking up transform from frame [base_link] to frame [odom])
... After 20 minutes...
[world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 3) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 4) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 5) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 6) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 4) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 5) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 6) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 5) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 6) -> Function send_any_unsent_changes [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Cannot add RTPS submesage to the CDRMessage. Buffer too small -> Function insert_submessage [world_model-4] 2019-07-09 11:30:03.693 [RTPS_WRITER Error] Error sending fragment (1708, 6) -> Function send_any_unsent_changes
Feature request
Feature description
Implementation considerations