Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use relative names for topics #415

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions ros/rviz/kiss_icp.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Best Effort
Value: /kiss/frame
Value: kiss/frame
Use Fixed Frame: true
Use rainbow: true
Value: true
Expand Down Expand Up @@ -93,7 +93,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Best Effort
Value: /kiss/keypoints
Value: kiss/keypoints
Use Fixed Frame: true
Use rainbow: true
Value: false
Expand Down Expand Up @@ -127,7 +127,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Best Effort
Value: /kiss/local_map
Value: kiss/local_map
Use Fixed Frame: true
Use rainbow: true
Value: true
Expand Down Expand Up @@ -170,7 +170,7 @@ Visualization Manager:
Filter size: 10
History Policy: Keep Last
Reliability Policy: Best Effort
Value: /kiss/odometry
Value: kiss/odometry
Value: true
Enabled: true
Global Options:
Expand Down
9 changes: 4 additions & 5 deletions ros/src/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,11 @@ OdometryServer::OdometryServer(const rclcpp::NodeOptions &options)

// Initialize publishers
rclcpp::QoS qos((rclcpp::SystemDefaultsQoS().keep_last(1).durability_volatile()));
odom_publisher_ = create_publisher<nav_msgs::msg::Odometry>("/kiss/odometry", qos);
odom_publisher_ = create_publisher<nav_msgs::msg::Odometry>("kiss/odometry", qos);
if (publish_debug_clouds_) {
frame_publisher_ = create_publisher<sensor_msgs::msg::PointCloud2>("/kiss/frame", qos);
kpoints_publisher_ =
create_publisher<sensor_msgs::msg::PointCloud2>("/kiss/keypoints", qos);
map_publisher_ = create_publisher<sensor_msgs::msg::PointCloud2>("/kiss/local_map", qos);
frame_publisher_ = create_publisher<sensor_msgs::msg::PointCloud2>("kiss/frame", qos);
kpoints_publisher_ = create_publisher<sensor_msgs::msg::PointCloud2>("kiss/keypoints", qos);
map_publisher_ = create_publisher<sensor_msgs::msg::PointCloud2>("kiss/local_map", qos);
}

// Initialize the transform broadcaster
Expand Down