Skip to content

Commit a71a5f2

Browse files
[WIP fixing CI] changing gazebo base to my fork for testing (#2034)
* changing gazebo base to my fork for testing * adding buffer header per TF2 API changes * moving header to header
1 parent be38a7a commit a71a5f2

File tree

2 files changed

+2
-1
lines changed

2 files changed

+2
-1
lines changed

nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
#include "rclcpp_action/rclcpp_action.hpp"
2929
#include "tf2_ros/transform_listener.h"
3030
#include "tf2_ros/create_timer_ros.h"
31+
#include "tf2_ros/buffer.h"
3132

3233
namespace nav2_bt_navigator
3334
{

tools/underlay.repos

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ repositories:
99
version: ros2
1010
ros-simulation/gazebo_ros_pkgs:
1111
type: git
12-
url: https://github.com/ros-simulation/gazebo_ros_pkgs.git
12+
url: https://github.com/stevemacenski/gazebo_ros_pkgs.git
1313
version: ros2
1414
ros-perception/image_common:
1515
type: git

0 commit comments

Comments
 (0)