diff --git a/README.md b/README.md
index 8f30f0cd..f0d95a05 100644
--- a/README.md
+++ b/README.md
@@ -59,7 +59,7 @@ For advanced instructions on the Python pacakge plase see [this README](python/R
ROS 2
```sh
-git clone https://github.com/PRBonn/kiss-icp && colcon build
+cd ~/ros2_ws/src/ && git clone https://github.com/PRBonn/kiss-icp && cd ~/ros2_ws/ && colcon build --packages-select kiss_icp
```
diff --git a/ros/ros2/OdometryServer.cpp b/ros/ros2/OdometryServer.cpp
index dfd8b1d3..0ddedb95 100644
--- a/ros/ros2/OdometryServer.cpp
+++ b/ros/ros2/OdometryServer.cpp
@@ -81,7 +81,7 @@ OdometryServer::OdometryServer(const rclcpp::NodeOptions &options)
std::bind(&OdometryServer::RegisterFrame, this, std::placeholders::_1));
// Initialize publishers
- rclcpp::QoS qos((rclcpp::SystemDefaultsQoS()));
+ rclcpp::QoS qos((rclcpp::SystemDefaultsQoS().keep_last(1).durability_volatile()));
odom_publisher_ = create_publisher("/kiss/odometry", qos);
traj_publisher_ = create_publisher("/kiss/trajectory", qos);
path_msg_.header.frame_id = odom_frame_;
@@ -214,3 +214,6 @@ void OdometryServer::PublishClouds(const std::vector frame,
}
}
} // namespace kiss_icp_ros
+
+#include "rclcpp_components/register_node_macro.hpp"
+RCLCPP_COMPONENTS_REGISTER_NODE(kiss_icp_ros::OdometryServer)
diff --git a/ros/ros2/OdometryServer.hpp b/ros/ros2/OdometryServer.hpp
index 13726d3a..418e0d2c 100644
--- a/ros/ros2/OdometryServer.hpp
+++ b/ros/ros2/OdometryServer.hpp
@@ -94,10 +94,3 @@ class OdometryServer : public rclcpp::Node {
};
} // namespace kiss_icp_ros
-
-#include "rclcpp_components/register_node_macro.hpp"
-
-// Register the component with class_loader.
-// This acts as a sort of entry point, allowing the component to be
-// discoverable when its library is being loaded into a running process.
-RCLCPP_COMPONENTS_REGISTER_NODE(kiss_icp_ros::OdometryServer)
diff --git a/ros/rviz/kiss_icp_ros2.rviz b/ros/rviz/kiss_icp_ros2.rviz
index e2949cc4..918ff216 100644
--- a/ros/rviz/kiss_icp_ros2.rviz
+++ b/ros/rviz/kiss_icp_ros2.rviz
@@ -58,7 +58,7 @@ Visualization Manager:
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
- Reliability Policy: Reliable
+ Reliability Policy: Best Effort
Value: /kiss/frame
Use Fixed Frame: true
Use rainbow: true
@@ -92,7 +92,7 @@ Visualization Manager:
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
- Reliability Policy: Reliable
+ Reliability Policy: Best Effort
Value: /kiss/keypoints
Use Fixed Frame: true
Use rainbow: true
@@ -126,7 +126,7 @@ Visualization Manager:
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
- Reliability Policy: Reliable
+ Reliability Policy: Best Effort
Value: /kiss/local_map
Use Fixed Frame: true
Use rainbow: true
@@ -171,7 +171,7 @@ Visualization Manager:
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
- Reliability Policy: Reliable
+ Reliability Policy: Best Effort
Value: /kiss/odometry
Value: true
- Alpha: 1
@@ -199,7 +199,7 @@ Visualization Manager:
Durability Policy: Volatile
Filter size: 10
History Policy: Keep Last
- Reliability Policy: Reliable
+ Reliability Policy: Best Effort
Value: /kiss/trajectory
Value: true
Enabled: true