Skip to content
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/src/OdometryServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/string.hpp>
#include <std_srvs/srv/empty.hpp>
#include <tf2_ros/static_transform_broadcaster.hpp>
#include <tf2_ros/transform_broadcaster.hpp>

namespace {
Sophus::SE3d LookupTransform(const std::string &target_frame,
const std::string &source_frame,
Expand Down Expand Up @@ -152,7 +155,7 @@ void OdometryServer::initializeParameters(kiss_icp::pipeline::KISSConfig &config
RCLCPP_INFO(this->get_logger(), "\tMax number of threads: %d", config.max_num_threads);
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");
"[WARNING] max_range is smaller than min_range, setting min_range to 0.0");
config.min_range = 0.0;
}
}
Expand Down
7 changes: 3 additions & 4 deletions ros/src/OdometryServer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,16 +26,15 @@
#include "kiss_icp/pipeline/KissICP.hpp"

// ROS 2
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>

#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/header.hpp>
#include <std_srvs/srv/empty.hpp>
#include <string>
#include <tf2_ros/buffer.hpp>
#include <tf2_ros/transform_broadcaster.hpp>
#include <tf2_ros/transform_listener.hpp>

namespace kiss_icp_ros {

Expand Down
Loading