Skip to content

Commit

Permalink
Change stuff around
Browse files Browse the repository at this point in the history
  • Loading branch information
nachovizzo committed Oct 2, 2023
1 parent b9e7950 commit 161ec43
Showing 1 changed file with 2 additions and 4 deletions.
6 changes: 2 additions & 4 deletions ros/ros2/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,17 +86,15 @@ OdometryServer::OdometryServer(const rclcpp::NodeOptions &options)
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);
traj_publisher_ = create_publisher<nav_msgs::msg::Path>("/kiss/trajectory", qos);
path_msg_.header.frame_id = odom_frame_;

// Initialize the transform broadcaster
tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);
tf2_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf2_buffer_->setUsingDedicatedThread(true);
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_);

// Initialize trajectory publisher
path_msg_.header.frame_id = odom_frame_;
traj_publisher_ = create_publisher<nav_msgs::msg::Path>("/kiss/trajectory", qos);

RCLCPP_INFO(this->get_logger(), "KISS-ICP ROS 2 odometry node initialized");
}

Expand Down

0 comments on commit 161ec43

Please sign in to comment.