Skip to content

Commit

Permalink
disable trajectory publisher by default
Browse files Browse the repository at this point in the history
as message grows without bound, requires increasing CPU resources and eventually slows down processing rate
  • Loading branch information
PGotzmann committed Oct 16, 2023
1 parent 0e50f16 commit 3c17e06
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 5 deletions.
14 changes: 9 additions & 5 deletions ros/ros2/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ OdometryServer::OdometryServer() : rclcpp::Node("odometry_node") {
config_.max_points_per_voxel = declare_parameter<int>("max_points_per_voxel", config_.max_points_per_voxel);
config_.initial_threshold = declare_parameter<double>("initial_threshold", config_.initial_threshold);
config_.min_motion_th = declare_parameter<double>("min_motion_th", config_.min_motion_th);
publish_trajectory_ = declare_parameter<bool>("publish_trajectory", false);
if (config_.max_range < config_.min_range) {
RCLCPP_WARN(get_logger(), "[WARNING] max_range is smaller than min_range, settng min_range to 0.0");
config_.min_range = 0.0;
Expand Down Expand Up @@ -186,11 +187,14 @@ void OdometryServer::RegisterFrame(const sensor_msgs::msg::PointCloud2::SharedPt
odom_publisher_->publish(odom_msg);

// publish trajectory msg
geometry_msgs::msg::PoseStamped pose_msg;
pose_msg.pose = odom_msg.pose.pose;
pose_msg.header = odom_msg.header;
path_msg_.poses.push_back(pose_msg);
traj_publisher_->publish(path_msg_);
// path message grows without bound! enable only for debug purposes
if (publish_trajectory_) {
geometry_msgs::msg::PoseStamped pose_msg;
pose_msg.pose = odom_msg.pose.pose;
pose_msg.header = odom_msg.header;
path_msg_.poses.push_back(pose_msg);
traj_publisher_->publish(path_msg_);
}

// Publish KISS-ICP internal data, just for debugging
std_msgs::msg::Header frame_header = msg.header;
Expand Down
1 change: 1 addition & 0 deletions ros/ros2/OdometryServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ class OdometryServer : public rclcpp::Node {
/// Path publisher
nav_msgs::msg::Path path_msg_;
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr traj_publisher_;
bool publish_trajectory_ = false;

/// KISS-ICP
kiss_icp::pipeline::KissICP odometry_;
Expand Down

0 comments on commit 3c17e06

Please sign in to comment.