diff --git a/include/slam_toolbox/slam_toolbox_common.hpp b/include/slam_toolbox/slam_toolbox_common.hpp index 9274ba545..8e43a6e38 100644 --- a/include/slam_toolbox/slam_toolbox_common.hpp +++ b/include/slam_toolbox/slam_toolbox_common.hpp @@ -36,8 +36,8 @@ #include "tf2_ros/create_timer_ros.h" #include "tf2_ros/message_filter.h" #include "tf2/LinearMath/Matrix3x3.h" -#include "tf2_geometry_msgs/tf2_geometry_msgs.h" -#include "tf2_sensor_msgs/tf2_sensor_msgs.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" +#include "tf2_sensor_msgs/tf2_sensor_msgs.hpp" #include "pluginlib/class_loader.hpp" diff --git a/include/slam_toolbox/toolbox_types.hpp b/include/slam_toolbox/toolbox_types.hpp index f9e6b20c4..c634d3b7c 100644 --- a/include/slam_toolbox/toolbox_types.hpp +++ b/include/slam_toolbox/toolbox_types.hpp @@ -24,7 +24,7 @@ #include #include "tf2_ros/buffer.h" -#include "tf2_geometry_msgs/tf2_geometry_msgs.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/transform_datatypes.h" // god... getting this to work in ROS2 was a real pain diff --git a/rviz_plugin/slam_toolbox_rviz_plugin.hpp b/rviz_plugin/slam_toolbox_rviz_plugin.hpp index be89b1e49..dafa5d0b7 100644 --- a/rviz_plugin/slam_toolbox_rviz_plugin.hpp +++ b/rviz_plugin/slam_toolbox_rviz_plugin.hpp @@ -41,7 +41,7 @@ #include "rviz_common/panel.hpp" #include "slam_toolbox/toolbox_msgs.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" -#include "tf2_geometry_msgs/tf2_geometry_msgs.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" class QLineEdit; class QSpinBox; diff --git a/src/slam_toolbox_common.cpp b/src/slam_toolbox_common.cpp index 5848720d3..f0d7f127f 100644 --- a/src/slam_toolbox_common.cpp +++ b/src/slam_toolbox_common.cpp @@ -163,7 +163,7 @@ void SlamToolbox::setParams() } smapper_->configure(shared_from_this()); - this->declare_parameter("paused_new_measurements"); + this->declare_parameter("paused_new_measurements",rclcpp::ParameterType::PARAMETER_BOOL); this->set_parameter({"paused_new_measurements", false}); } @@ -301,8 +301,8 @@ bool SlamToolbox::shouldStartWithPoseGraph( { // if given a map to load at run time, do it. this->declare_parameter("map_file_name", std::string("")); - auto map_start_pose = this->declare_parameter("map_start_pose"); - auto map_start_at_dock = this->declare_parameter("map_start_at_dock"); + auto map_start_pose = this->declare_parameter("map_start_pose",rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY); + auto map_start_at_dock = this->declare_parameter("map_start_at_dock",rclcpp::ParameterType::PARAMETER_BOOL); filename = this->get_parameter("map_file_name").as_string(); if (!filename.empty()) { std::vector read_pose;