Skip to content
Snippets Groups Projects
Commit 828a388f authored by Carl Delsey's avatar Carl Delsey
Browse files

Revert "Merge pull request #538 from sloretz/amcl-use-only-one-node"

This reverts commit 97675013, reversing
changes made to 1ae4a549.

Changes are no longer needed since the error this fixed has been turned
into a warning.
parent 3f65576a
No related branches found
No related tags found
No related merge requests found
...@@ -96,7 +96,7 @@ AmclNode::AmclNode() ...@@ -96,7 +96,7 @@ AmclNode::AmclNode()
tfb_.reset(new tf2_ros::TransformBroadcaster(node_)); tfb_.reset(new tf2_ros::TransformBroadcaster(node_));
tf_.reset(new tf2_ros::Buffer(get_clock())); tf_.reset(new tf2_ros::Buffer(get_clock()));
tfl_.reset(new tf2_ros::TransformListener(*tf_, node_, false)); tfl_.reset(new tf2_ros::TransformListener(*tf_));
rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default; rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
custom_qos_profile.depth = 2; custom_qos_profile.depth = 2;
......
...@@ -16,7 +16,6 @@ ...@@ -16,7 +16,6 @@
#define NAV2_TASKS__SERVICE_CLIENT_HPP_ #define NAV2_TASKS__SERVICE_CLIENT_HPP_
#include <string> #include <string>
#include <vector>
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
namespace nav2_tasks namespace nav2_tasks
...@@ -28,14 +27,7 @@ class ServiceClient ...@@ -28,14 +27,7 @@ class ServiceClient
public: public:
explicit ServiceClient(const std::string & name) explicit ServiceClient(const std::string & name)
{ {
node_ = rclcpp::Node::make_shared(name + "_Node", node_ = rclcpp::Node::make_shared(name + "_Node");
"",
rclcpp::contexts::default_context::get_global_default_context(),
std::vector<std::string>(),
std::vector<rclcpp::Parameter>(),
false, // ignore global parameters, so this node doesn't get renamed
false,
false);
client_ = node_->create_client<ServiceT>(name); client_ = node_->create_client<ServiceT>(name);
} }
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment