Skip to content

Commit

Permalink
Fixing the broken build.
Browse files Browse the repository at this point in the history
  • Loading branch information
Carl Delsey committed Feb 11, 2019
1 parent 828a388 commit 0436639
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 8 deletions.
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
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 0436639

Please sign in to comment.