Skip to content

Commit

Permalink
Merge pull request #560 from crdelsey/quickfixes
Browse files Browse the repository at this point in the history
Fixing the broken build
  • Loading branch information
Carl Delsey authored Feb 12, 2019
2 parents 3f65576 + 0436639 commit 0deebc1
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 18 deletions.
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ AmclNode::AmclNode()

tfb_.reset(new tf2_ros::TransformBroadcaster(node_));
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;
custom_qos_profile.depth = 2;
Expand Down
9 changes: 3 additions & 6 deletions nav2_dwb_controller/dwb_plugins/test/twist_gen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,12 +74,9 @@ std::vector<rclcpp::Parameter> getDefaultKinematicParameters()

rclcpp::Node::SharedPtr makeTestNode(const std::string & name)
{
return rclcpp::Node::make_shared(
name,
"", // namespace
rclcpp::contexts::default_context::get_global_default_context(),
std::vector<std::string>(), // arguments
getDefaultKinematicParameters());
rclcpp::NodeOptions node_options;
node_options.initial_parameters(getDefaultKinematicParameters());
return rclcpp::Node::make_shared(name, node_options);
}

void checkLimits(
Expand Down
10 changes: 1 addition & 9 deletions nav2_tasks/include/nav2_tasks/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define NAV2_TASKS__SERVICE_CLIENT_HPP_

#include <string>
#include <vector>
#include "rclcpp/rclcpp.hpp"

namespace nav2_tasks
Expand All @@ -28,14 +27,7 @@ class ServiceClient
public:
explicit ServiceClient(const std::string & name)
{
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);
node_ = rclcpp::Node::make_shared(name + "_Node");
client_ = node_->create_client<ServiceT>(name);
}

Expand Down
12 changes: 10 additions & 2 deletions tools/ros2_dependencies.repos
Original file line number Diff line number Diff line change
Expand Up @@ -9,5 +9,13 @@ repositories:
version: ros2
gazebo_ros_pkgs:
type: git
url: https://github.com/ros-simulation/gazebo_ros_pkgs.git
version: 3.0.0
url: https://github.com/crdelsey/gazebo_ros_pkgs.git
version: nodeoptions
image_common:
type: git
url: https://github.com/crdelsey/image_common.git
version: nodeoptions
vision_opencv:
type: git
url: https://github.com/ros-perception/vision_opencv.git
version: ros2

0 comments on commit 0deebc1

Please sign in to comment.