Skip to content

Commit

Permalink
Change durability policy of mesh display to transient_local (#36)
Browse files Browse the repository at this point in the history
Co-authored-by: Timon Engelke <timon.engelke@dlr.de>
  • Loading branch information
timonegk and timonegk committed Mar 28, 2024
1 parent 60dfa15 commit df5aa87
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion launch/reach_study_config.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ Visualization Manager:
"": true
Topic:
Depth: 5
Durability Policy: Volatile
Durability Policy: Transient Local
Filter size: 10
History Policy: Keep Last
Reliability Policy: Reliable
Expand Down
2 changes: 1 addition & 1 deletion src/display/ros_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ ROSDisplay::ROSDisplay(std::string kinematic_base_frame, double marker_scale, bo
joint_state_pub_ =
reach_ros::utils::getNodeInstance()->create_publisher<sensor_msgs::msg::JointState>(JOINT_STATES_TOPIC, 1);
mesh_pub_ =
reach_ros::utils::getNodeInstance()->create_publisher<visualization_msgs::msg::Marker>(MESH_MARKER_TOPIC, 1);
reach_ros::utils::getNodeInstance()->create_publisher<visualization_msgs::msg::Marker>(MESH_MARKER_TOPIC, rclcpp::QoS(1).transient_local());
neighbors_pub_ =
reach_ros::utils::getNodeInstance()->create_publisher<visualization_msgs::msg::Marker>(NEIGHBORS_MARKER_TOPIC, 1);
}
Expand Down

0 comments on commit df5aa87

Please sign in to comment.