diff --git a/include/slam_toolbox/loop_closure_assistant.hpp b/include/slam_toolbox/loop_closure_assistant.hpp index 86e141c2f..15d0f2b38 100644 --- a/include/slam_toolbox/loop_closure_assistant.hpp +++ b/include/slam_toolbox/loop_closure_assistant.hpp @@ -26,6 +26,7 @@ #include #include "tf2_ros/transform_broadcaster.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.h" #include "rclcpp/rclcpp.hpp" #include "interactive_markers/interactive_marker_server.hpp" diff --git a/include/slam_toolbox/slam_mapper.hpp b/include/slam_toolbox/slam_mapper.hpp index 869a632ef..a902cab5d 100644 --- a/include/slam_toolbox/slam_mapper.hpp +++ b/include/slam_toolbox/slam_mapper.hpp @@ -20,7 +20,9 @@ #define SLAM_TOOLBOX__SLAM_MAPPER_HPP_ #include +#include "geometry_msgs/msg/quaternion.hpp" #include "rclcpp/rclcpp.hpp" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.h" #include "slam_toolbox/toolbox_types.hpp" diff --git a/src/experimental/slam_toolbox_lifelong_node.cpp b/src/experimental/slam_toolbox_lifelong_node.cpp index 6a8401b78..2a4ddda08 100644 --- a/src/experimental/slam_toolbox_lifelong_node.cpp +++ b/src/experimental/slam_toolbox_lifelong_node.cpp @@ -27,7 +27,7 @@ int main(int argc, char ** argv) int stack_size = 40000000; { auto temp_node = std::make_shared("slam_toolbox"); - temp_node->declare_parameter("stack_size_to_use"); + temp_node->declare_parameter("stack_size_to_use", stack_size); if (temp_node->get_parameter("stack_size_to_use", stack_size)) { RCLCPP_INFO(temp_node->get_logger(), "Node using stack size %i", (int)stack_size); const rlim_t max_stack_size = stack_size; diff --git a/src/loop_closure_assistant.cpp b/src/loop_closure_assistant.cpp index a8e6d812f..b6355f7fe 100644 --- a/src/loop_closure_assistant.cpp +++ b/src/loop_closure_assistant.cpp @@ -21,6 +21,8 @@ #include "slam_toolbox/loop_closure_assistant.hpp" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" + namespace loop_closure_assistant {