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
4 changes: 2 additions & 2 deletions include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand Down
2 changes: 1 addition & 1 deletion include/slam_toolbox/toolbox_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <vector>

#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
Expand Down
2 changes: 1 addition & 1 deletion rviz_plugin/slam_toolbox_rviz_plugin.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
6 changes: 3 additions & 3 deletions src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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});
}

Expand Down Expand Up @@ -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<double> read_pose;
Expand Down