Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixing the broken build #560

Merged
2 commits merged into from
Feb 12, 2019
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
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