Skip to content
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
7 changes: 7 additions & 0 deletions ros/src/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,8 @@ 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);
pose_publisher_ =
create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>("kiss/pose", 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);
Expand Down Expand Up @@ -221,6 +223,11 @@ void OdometryServer::PublishOdometry(const Sophus::SE3d &kiss_pose,
odom_msg.pose.covariance[28] = orientation_covariance_;
odom_msg.pose.covariance[35] = orientation_covariance_;
odom_publisher_->publish(std::move(odom_msg));

geometry_msgs::msg::PoseWithCovarianceStamped pose_msg;
pose_msg.header = odom_msg.header;
pose_msg.pose = odom_msg.pose;
pose_publisher_->publish(pose_msg);
}

void OdometryServer::PublishClouds(const std::vector<Eigen::Vector3d> &frame,
Expand Down
2 changes: 2 additions & 0 deletions ros/src/OdometryServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "kiss_icp/pipeline/KissICP.hpp"

// ROS 2
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -76,6 +77,7 @@ class OdometryServer : public rclcpp::Node {

/// Data publishers.
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_publisher_;
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pose_publisher_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr frame_publisher_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr kpoints_publisher_;
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr map_publisher_;
Expand Down