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

Nacho/re enable ipc #253

Merged
merged 7 commits into from
Nov 23, 2023
Merged
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
5 changes: 4 additions & 1 deletion ros/ros2/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<nav_msgs::msg::Odometry>("/kiss/odometry", qos);
traj_publisher_ = create_publisher<nav_msgs::msg::Path>("/kiss/trajectory", qos);
path_msg_.header.frame_id = odom_frame_;
Expand Down Expand Up @@ -214,3 +214,6 @@ void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> frame,
}
}
} // namespace kiss_icp_ros

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(kiss_icp_ros::OdometryServer)
7 changes: 0 additions & 7 deletions ros/ros2/OdometryServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
10 changes: 5 additions & 5 deletions ros/rviz/kiss_icp_ros2.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
Loading