diff --git a/ros/src/OdometryServer.cpp b/ros/src/OdometryServer.cpp index e37c9c3b..c4b0fbb3 100644 --- a/ros/src/OdometryServer.cpp +++ b/ros/src/OdometryServer.cpp @@ -45,6 +45,9 @@ #include #include #include +#include +#include + namespace { Sophus::SE3d LookupTransform(const std::string &target_frame, const std::string &source_frame, @@ -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; } } diff --git a/ros/src/OdometryServer.hpp b/ros/src/OdometryServer.hpp index c758d02a..78838d5c 100644 --- a/ros/src/OdometryServer.hpp +++ b/ros/src/OdometryServer.hpp @@ -26,16 +26,15 @@ #include "kiss_icp/pipeline/KissICP.hpp" // ROS 2 -#include -#include -#include - #include #include #include #include #include #include +#include +#include +#include namespace kiss_icp_ros {